提交 b82d0e16 编写于 作者: M me-no-dev

latest IDF, 240MHz and BLE enabled libs

上级 1d1aeecd
......@@ -17,7 +17,7 @@ esp32.build.core=esp32
esp32.build.variant=esp32
esp32.build.board=ESP32_DEV
esp32.build.f_cpu=160000000L
esp32.build.f_cpu=240000000L
esp32.build.flash_mode=dio
esp32.build.flash_size=4MB
......@@ -57,7 +57,7 @@ esp320.build.core=esp32
esp320.build.variant=esp320
esp320.build.board=ESP320
esp320.build.f_cpu=160000000L
esp320.build.f_cpu=240000000L
esp320.build.flash_mode=qio
esp320.build.flash_size=4MB
......@@ -97,7 +97,7 @@ nano32.build.core=esp32
nano32.build.variant=nano32
nano32.build.board=NANO32
nano32.build.f_cpu=160000000L
nano32.build.f_cpu=240000000L
nano32.build.flash_mode=dio
nano32.build.flash_size=4MB
......@@ -137,7 +137,7 @@ lolin32.build.core=esp32
lolin32.build.variant=lolin32
lolin32.build.board=LoLin32
lolin32.build.f_cpu=160000000L
lolin32.build.f_cpu=240000000L
lolin32.build.flash_mode=dio
lolin32.build.flash_size=4MB
......@@ -177,7 +177,7 @@ espea32.build.core=esp32
espea32.build.variant=espea32
espea32.build.board=ESPea32
espea32.build.f_cpu=160000000L
espea32.build.f_cpu=240000000L
espea32.build.flash_mode=dio
espea32.build.flash_size=4MB
......@@ -217,7 +217,7 @@ quantum.build.core=esp32
quantum.build.variant=quantum
quantum.build.board=QUANTUM
quantum.build.f_cpu=160000000L
quantum.build.f_cpu=240000000L
quantum.build.flash_mode=qio
quantum.build.flash_size=16MB
......@@ -257,7 +257,7 @@ node32s.build.core=esp32
node32s.build.variant=node32s
node32s.build.board=Node32s
node32s.build.f_cpu=160000000L
node32s.build.f_cpu=240000000L
node32s.build.flash_mode=dio
node32s.build.flash_size=4MB
......
......@@ -4,8 +4,10 @@
* Espressif IoT Development Framework Configuration
*
*/
#define CONFIG_ESP32_PHY_MAX_TX_POWER 20
#define CONFIG_TRACEMEM_RESERVE_DRAM 0x0
#define CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE 1
#define CONFIG_MEMMAP_BT 1
#define CONFIG_SECURE_BOOTLOADER_DISABLED 1
#define CONFIG_ESPTOOLPY_FLASHSIZE_4MB 1
#define CONFIG_ESPTOOLPY_FLASHFREQ "80m"
......@@ -13,10 +15,10 @@
#define CONFIG_ESPTOOLPY_FLASHSIZE "4MB"
#define CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL 1
#define CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS 1
#define CONFIG_BT_RESERVE_DRAM 0x0
#define CONFIG_BT_RESERVE_DRAM 0x10000
#define CONFIG_LOG_BOOTLOADER_LEVEL_ERROR 1
#define CONFIG_LWIP_MAX_SOCKETS 4
#define CONFIG_ESP32_DEFAULT_CPU_FREQ_160 1
#define CONFIG_ESP32_ENABLE_STACK_BT 1
#define CONFIG_ULP_COPROC_RESERVE_MEM 0
#define CONFIG_ESPTOOLPY_BAUD 921600
#define CONFIG_TOOLPREFIX "xtensa-esp32-elf-"
......@@ -24,8 +26,8 @@
#define CONFIG_LWIP_THREAD_LOCAL_STORAGE_INDEX 0
#define CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN 16384
#define CONFIG_AUTOSTART_ARDUINO 1
#define CONFIG_ESP32_ENABLE_STACK_WIFI 1
#define CONFIG_LOG_DEFAULT_LEVEL_ERROR 1
#define CONFIG_MBEDTLS_MPI_USE_INTERRUPT 1
#define CONFIG_MAIN_TASK_STACK_SIZE 4096
#define CONFIG_ESPTOOLPY_FLASHMODE "dio"
#define CONFIG_LOG_DEFAULT_LEVEL 1
......@@ -36,26 +38,32 @@
#define CONFIG_PARTITION_TABLE_FILENAME "partitions_singleapp.csv"
#define CONFIG_LWIP_DHCP_MAX_NTP_SERVERS 1
#define CONFIG_PARTITION_TABLE_SINGLE_APP 1
#define CONFIG_WIFI_ENABLED 1
#define CONFIG_ESPTOOLPY_FLASHFREQ_80M 1
#define CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE 2048
#define CONFIG_PHY_DATA_OFFSET 0xf000
#define CONFIG_PARTITION_TABLE_CUSTOM_APP_BIN_OFFSET 0x10000
#define CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ 160
#define CONFIG_MBEDTLS_MPI_INTERRUPT_NUM 18
#define CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ 240
#define CONFIG_MBEDTLS_HARDWARE_AES 1
#define CONFIG_FREERTOS_HZ 1000
#define CONFIG_FREERTOS_ASSERT_FAIL_ABORT 1
#define CONFIG_MONITOR_BAUD_115200B 1
#define CONFIG_LOG_BOOTLOADER_LEVEL 1
#define CONFIG_ESPTOOLPY_BAUD_OTHER_VAL 115200
#define CONFIG_ESP32_DEFAULT_CPU_FREQ_240 1
#define CONFIG_LWIP_SO_REUSE 1
#define CONFIG_BT_ENABLED 1
#define CONFIG_MONITOR_BAUD 115200
#define CONFIG_FREERTOS_CORETIMER_0 1
#define CONFIG_PARTITION_TABLE_CUSTOM_FILENAME "partitions.csv"
#define CONFIG_FREERTOS_ISR_STACKSIZE 1536
#define CONFIG_OPTIMIZATION_LEVEL_DEBUG 1
#define CONFIG_ESP32_PHY_AUTO_INIT 1
#define CONFIG_SYSTEM_EVENT_QUEUE_SIZE 32
#define CONFIG_ESPTOOLPY_BAUD_921600B 1
#define CONFIG_APP_OFFSET 0x10000
#define CONFIG_MEMMAP_SMP 1
#define CONFIG_MBEDTLS_HARDWARE_MPI 1
#define CONFIG_MONITOR_BAUD_OTHER_VAL 115200
#define CONFIG_ESPTOOLPY_PORT "/dev/tty.SLAB_USBtoUART"
#define CONFIG_ESP32_PANIC_PRINT_HALT 1
......
#ifndef __PCNT_H__
#define __PCNT_H__
#include <esp_types.h>
#include "esp_intr.h"
#include "esp_err.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/xtensa_api.h"
#include "soc/soc.h"
#include "soc/pcnt_reg.h"
#include "soc/pcnt_struct.h"
#include "soc/gpio_sig_map.h"
#include "driver/gpio.h"
#ifdef __cplusplus
extern "C" {
#endif
#define PCNT_PIN_NOT_USED (-1) /*!< Pin are not used */
typedef enum {
PCNT_MODE_KEEP = 0, /*!< Control mode: won't change counter mode*/
PCNT_MODE_REVERSE = 1, /*!< Control mode: invert counter mode(increase -> decrease, decrease -> increase);*/
PCNT_MODE_DISABLE = 2, /*!< Control mode: Inhibit counter(counter value will not change in this condition)*/
PCNT_MODE_MAX
} pcnt_ctrl_mode_t;
typedef enum {
PCNT_COUNT_DIS = 0, /*!< Counter mode: Decrease counter value*/
PCNT_COUNT_INC = 1, /*!< Counter mode: Increase counter value*/
PCNT_COUNT_DEC = 2, /*!< Counter mode: Inhibit counter(counter value will not change in this condition)*/
PCNT_COUNT_MAX
} pcnt_count_mode_t;
typedef enum {
PCNT_UNIT_0 = 0, /*!< PCNT unit0 */
PCNT_UNIT_1 = 1, /*!< PCNT unit1 */
PCNT_UNIT_2 = 2, /*!< PCNT unit2 */
PCNT_UNIT_3 = 3, /*!< PCNT unit3 */
PCNT_UNIT_4 = 4, /*!< PCNT unit4 */
PCNT_UNIT_5 = 5, /*!< PCNT unit5 */
PCNT_UNIT_6 = 6, /*!< PCNT unit6 */
PCNT_UNIT_7 = 7, /*!< PCNT unit7 */
PCNT_UNIT_MAX,
} pcnt_unit_t;
typedef enum{
PCNT_CHANNEL_0 = 0x00, /*!< PCNT channel0 */
PCNT_CHANNEL_1 = 0x01, /*!< PCNT channel1 */
PCNT_CHANNEL_MAX,
} pcnt_channel_t;
typedef enum {
PCNT_EVT_L_LIM = 0, /*!< PCNT watch point event: Minimum counter value */
PCNT_EVT_H_LIM = 1, /*!< PCNT watch point event: Maximum counter value*/
PCNT_EVT_THRES_0 = 2, /*!< PCNT watch point event: threshold0 value event*/
PCNT_EVT_THRES_1 = 3, /*!< PCNT watch point event: threshold1 value event*/
PCNT_EVT_ZERO = 4, /*!< PCNT watch point event: counter value zero event*/
PCNT_EVT_MAX
} pcnt_evt_type_t;
/**
* @brief Pulse Counter configure struct
*/
typedef struct {
int pulse_gpio_num; /*!< Pulse input gpio_num, if you want to use gpio16, pulse_gpio_num = 16, a negative value will be ignored */
int ctrl_gpio_num; /*!< Contol signal input gpio_num, a negative value will be ignored*/
pcnt_ctrl_mode_t lctrl_mode; /*!< PCNT low control mode*/
pcnt_ctrl_mode_t hctrl_mode; /*!< PCNT high control mode*/
pcnt_count_mode_t pos_mode; /*!< PCNT positive edge count mode*/
pcnt_count_mode_t neg_mode; /*!< PCNT negative edge count mode*/
int16_t counter_h_lim; /*!< Maximum counter value */
int16_t counter_l_lim; /*!< Minimum counter value */
pcnt_unit_t unit; /*!< PCNT unit number */
pcnt_channel_t channel; /*!< the PCNT channel */
} pcnt_config_t;
/**
* @brief Configure Pulse Counter unit
*
* @param pcnt_config Pointer of Pulse Counter unit configure parameter
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_unit_config(pcnt_config_t *pcnt_config);
/**
* @brief Get pulse counter value
*
* @param pcnt_unit Pulse Counter unit number
* @param count Pointer to accept counter value
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_get_counter_value(pcnt_unit_t pcnt_unit, int16_t* count);
/**
* @brief Pause PCNT counter of PCNT unit
*
* @param pcnt_unit PCNT unit number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_counter_pause(pcnt_unit_t pcnt_unit);
/**
* @brief Resume counting for PCNT counter
*
* @param pcnt_unit PCNT unit number, select from pcnt_unit_t
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_counter_resume(pcnt_unit_t pcnt_unit);
/**
* @brief Clear and reset PCNT counter value to zero
*
* @param pcnt_unit PCNT unit number, select from pcnt_unit_t
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_counter_clear(pcnt_unit_t pcnt_unit);
/**
* @brief Enable PCNT interrupt for PCNT unit
* @note
* Each Pulse counter unit has five watch point events that share the same interrupt.
* Configure events with pcnt_event_enable() and pcnt_event_disable()
*
* @param pcnt_unit PCNT unit number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_intr_enable(pcnt_unit_t pcnt_unit);
/**
* @brief Disable PCNT interrupt for PCNT uint
*
* @param pcnt_unit PCNT unit number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_intr_disable(pcnt_unit_t pcnt_unit);
/**
* @brief Enable PCNT event of PCNT unit
*
* @param unit PCNT unit number
* @param evt_type Watch point event type.
* All enabled events share the same interrupt (one interrupt per pulse counter unit).
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_event_enable(pcnt_unit_t unit, pcnt_evt_type_t evt_type);
/**
* @brief Disable PCNT event of PCNT unit
*
* @param unit PCNT unit number
* @param evt_type Watch point event type.
* All enabled events share the same interrupt (one interrupt per pulse counter unit).
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_event_disable(pcnt_unit_t unit, pcnt_evt_type_t evt_type);
/**
* @brief Set PCNT event value of PCNT unit
*
* @param unit PCNT unit number
* @param evt_type Watch point event type.
* All enabled events share the same interrupt (one interrupt per pulse counter unit).
*
* @param value Counter value for PCNT event
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_set_event_value(pcnt_unit_t unit, pcnt_evt_type_t evt_type, int16_t value);
/**
* @brief Get PCNT event value of PCNT unit
*
* @param unit PCNT unit number
* @param evt_type Watch point event type.
* All enabled events share the same interrupt (one interrupt per pulse counter unit).
* @param value Pointer to accept counter value for PCNT event
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_get_event_value(pcnt_unit_t unit, pcnt_evt_type_t evt_type, int16_t *value);
/**
* @brief Register PCNT interrupt handler, the handler is an ISR.
* The handler will be attached to the same CPU core that this function is running on.
* @note
* Users should know that which CPU is running and then pick a INUM that is not used by system.
* We can find the information of INUM and interrupt level in soc.h.
*
* @param pcnt_intr_num PCNT interrupt number, check the info in soc.h, and please see the core-isa.h for more details
* @param fn Interrupt handler function.
* @note
* Note that the handler function MUST be defined with attribution of "IRAM_ATTR".
* @param arg Parameter for handler function
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Function pointer error.
*/
esp_err_t pcnt_isr_register(uint32_t pcnt_intr_num, void (*fn)(void*), void * arg);
/**
* @brief Configure PCNT pulse signal input pin and control input pin
*
* @param unit PCNT unit number
* @param channel PCNT channel number
* @param pulse_io Pulse signal input GPIO
* @note
* Set to PCNT_PIN_NOT_USED if unused.
* @param ctrl_io Control signal input GPIO
* @note
* Set to PCNT_PIN_NOT_USED if unused.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_set_pin(pcnt_unit_t unit, pcnt_channel_t channel, int pulse_io, int ctrl_io);
/**
* @brief Enable PCNT input filter
*
* @param unit PCNT unit number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_filter_enable(pcnt_unit_t unit);
/**
* @brief Disable PCNT input filter
*
* @param unit PCNT unit number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_filter_disable(pcnt_unit_t unit);
/**
* @brief Set PCNT filter value
*
* @param unit PCNT unit number
* @param filter_val PCNT signal filter value, counter in APB_CLK cycles.
* Any pulses lasting shorter than this will be ignored when the filter is enabled.
* @note
* filter_val is a 10-bit value, so the maximum filter_val should be limited to 1023.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_set_filter_value(pcnt_unit_t unit, uint16_t filter_val);
/**
* @brief Get PCNT filter value
*
* @param unit PCNT unit number
* @param filter_val Pointer to accept PCNT filter value.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_get_filter_value(pcnt_unit_t unit, uint16_t *filter_val);
/**
* @brief Set PCNT counter mode
*
* @param unit PCNT unit number
* @param channel PCNT channel number
* @param pos_mode Counter mode when detecting positive edge
* @param neg_mode Counter mode when detecting negative edge
* @param hctrl_mode Counter mode when control signal is high level
* @param lctrl_mode Counter mode when control signal is low level
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t pcnt_set_mode(pcnt_unit_t unit, pcnt_channel_t channel,
pcnt_count_mode_t pos_mode, pcnt_count_mode_t neg_mode,
pcnt_ctrl_mode_t hctrl_mode, pcnt_ctrl_mode_t lctrl_mode);
/**
* @addtogroup pcnt-examples
*
* @{
*
* EXAMPLE OF PCNT CONFIGURATION
* ==============================
* @code{c}
* //1. Config PCNT unit
* pcnt_config_t pcnt_config = {
* .pulse_gpio_num = 4, //set gpio4 as pulse input gpio
* .ctrl_gpio_num = 5, //set gpio5 as control gpio
* .channel = PCNT_CHANNEL_0, //use unit 0 channel 0
* .lctrl_mode = PCNT_MODE_REVERSE, //when control signal is low ,reverse the primary counter mode(inc->dec/dec->inc)
* .hctrl_mode = PCNT_MODE_KEEP, //when control signal is high,keep the primary counter mode
* .pos_mode = PCNT_COUNT_INC, //increment the counter
* .neg_mode = PCNT_COUNT_DIS, //keep the counter value
* .counter_h_lim = 10,
* .counter_l_lim = -10,
* };
* pcnt_unit_config(&pcnt_config); //init unit
* @endcode
*
* EXAMPLE OF PCNT EVENT SETTING
* ==============================
* @code{c}
* //2. Configure PCNT watchpoint event.
* pcnt_set_event_value(PCNT_UNIT_0, PCNT_EVT_THRES_1, 5); //set thres1 value
* pcnt_event_enable(PCNT_UNIT_0, PCNT_EVT_THRES_1); //enable thres1 event
* @endcode
*
* For more examples please refer to PCNT example code in IDF_PATH/examples
*
* @}
*/
#ifdef __cplusplus
}
#endif
#endif
......@@ -39,6 +39,8 @@ typedef enum {
PERIPH_PWM3_MODULE,
PERIPH_UHCI0_MODULE,
PERIPH_UHCI1_MODULE,
PERIPH_RMT_MODULE,
PERIPH_PCNT_MODULE,
} periph_module_t;
/**
......
此差异已折叠。
......@@ -167,25 +167,25 @@ esp_err_t uart_get_word_length(uart_port_t uart_num, uart_word_length_t* data_bi
* @brief Set UART stop bits.
*
* @param uart_num UART_NUM_0, UART_NUM_1 or UART_NUM_2
* @param bit_num UART stop bits
* @param stop_bits UART stop bits
*
* @return
* - ESP_OK Success
* - ESP_FAIL Fail
*/
esp_err_t uart_set_stop_bits(uart_port_t uart_num, uart_stop_bits_t bit_num);
esp_err_t uart_set_stop_bits(uart_port_t uart_num, uart_stop_bits_t stop_bits);
/**
* @brief Set UART stop bits.
*
* @param uart_num UART_NUM_0, UART_NUM_1 or UART_NUM_2
* @param stop_bit Pointer to accept value of UART stop bits.
* @param stop_bits Pointer to accept value of UART stop bits.
*
* @return
* - ESP_FAIL Parameter error
* - ESP_OK Success, result will be put in (*stop_bit)
*/
esp_err_t uart_get_stop_bits(uart_port_t uart_num, uart_stop_bits_t* stop_bit);
esp_err_t uart_get_stop_bits(uart_port_t uart_num, uart_stop_bits_t* stop_bits);
/**
* @brief Set UART parity.
......@@ -216,13 +216,13 @@ esp_err_t uart_get_parity(uart_port_t uart_num, uart_parity_t* parity_mode);
* @brief Set UART baud rate.
*
* @param uart_num UART_NUM_0, UART_NUM_1 or UART_NUM_2
* @param baud_rate UART baud-rate.
* @param baudrate UART baud rate.
*
* @return
* - ESP_FAIL Parameter error
* - ESP_OK Success
*/
esp_err_t uart_set_baudrate(uart_port_t uart_num, uint32_t baud_rate);
esp_err_t uart_set_baudrate(uart_port_t uart_num, uint32_t baudrate);
/**
* @brief Get UART bit-rate.
......@@ -241,7 +241,7 @@ esp_err_t uart_get_baudrate(uart_port_t uart_num, uint32_t* baudrate);
* @brief Set UART line inverse mode
*
* @param uart_num UART_NUM_0, UART_NUM_1 or UART_NUM_2
* @param inverse_mask Choose the wires that need to be inversed.
* @param inverse_mask Choose the wires that need to be inverted.
* Inverse_mask should be chosen from UART_INVERSE_RXD/UART_INVERSE_TXD/UART_INVERSE_RTS/UART_INVERSE_CTS, combine with OR operation.
*
* @return
......
......@@ -30,25 +30,34 @@ extern "C" {
*/
/**
* @brief Set the chip to deep-sleep mode.
*
* The device will automatically wake up after the deep-sleep time set
* by the users. Upon waking up, the device boots up from user_init.
*
* @attention The parameter time_in_us to be "uint64" is for further development.
* Only the low 32 bits of parameter time_in_us are avalable now.
*
* @param uint64 time_in_us : deep-sleep time, only the low 32bits are avalable now. unit: microsecond
*
* @return null
*/
void system_deep_sleep(uint64_t time_in_us);
* @brief Enter deep-sleep mode
*
* The device will automatically wake up after the deep-sleep time
* Upon waking up, the device calls deep sleep wake stub, and then proceeds
* to load application.
*
* This function does not return.
*
* @param time_in_us deep-sleep time, unit: microsecond
*/
void esp_deep_sleep(uint64_t time_in_us) __attribute__((noreturn));
/**
* @brief Enter deep-sleep mode
*
* Function has been renamed to esp_deep_sleep.
* This name is deprecated and will be removed in a future version.
*
* @param time_in_us deep-sleep time, unit: microsecond
*/
void system_deep_sleep(uint64_t time_in_us) __attribute__((noreturn, deprecated));
/**
* @brief Default stub to run on wake from deep sleep.
*
* Allows for executing code immediately on wake from sleep, before
* the software bootloader or esp-idf app has started up.
* the software bootloader or ESP-IDF app has started up.
*
* This function is weak-linked, so you can implement your own version
* to run code immediately when the chip wakes from
......
......@@ -44,6 +44,7 @@ typedef enum {
SYSTEM_EVENT_AP_STACONNECTED, /**< a station connected to ESP32 soft-AP */
SYSTEM_EVENT_AP_STADISCONNECTED, /**< a station disconnected from ESP32 soft-AP */
SYSTEM_EVENT_AP_PROBEREQRECVED, /**< Receive probe request packet in soft-AP interface */
SYSTEM_EVENT_AP_STA_GOT_IP6, /**< ESP32 station or ap interface v6IP addr is preferred */
SYSTEM_EVENT_MAX
} system_event_id_t;
......@@ -79,7 +80,11 @@ typedef struct {
typedef struct {
uint8_t pin_code[8]; /**< PIN code of station in enrollee mode */
}system_event_sta_wps_er_pin_t;
} system_event_sta_wps_er_pin_t;
typedef struct {
tcpip_adapter_ip6_info_t ip6_info;
} system_event_ap_sta_got_ip6_t;
typedef struct {
uint8_t mac[6]; /**< MAC address of the station connected to ESP32 soft-AP */
......@@ -106,6 +111,7 @@ typedef union {
system_event_ap_staconnected_t sta_connected; /**< a station connected to ESP32 soft-AP */
system_event_ap_stadisconnected_t sta_disconnected; /**< a station disconnected to ESP32 soft-AP */
system_event_ap_probe_req_rx_t ap_probereqrecved; /**< ESP32 soft-AP receive probe request packet */
system_event_ap_sta_got_ip6_t got_ip6; /**< ESP32 station or ap ipv6 addr state change to preferred */
} system_event_info_t;
typedef struct {
......
......@@ -82,126 +82,6 @@ extern "C" {
#define ESP_INTR_DISABLE(inum) \
xt_ints_off((1<<inum))
#define ESP_CCOMPARE_INTR_ENBALE() \
ESP_INTR_ENABLE(ETS_CCOMPARE_INUM)
#define ESP_CCOMPARE_INTR_DISBALE() \
ESP_INTR_DISABLE(ETS_CCOMPARE_INUM)
#define ESP_SPI1_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_SPI1_INUM)
#define ESP_SPI1_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_SPI1_INUM)
#define ESP_SPI2_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_SPI2_INUM)
#define ESP_PWM_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_PWM_INUM)
#define ESP_PWM_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_PWM_INUM)
#define ESP_SPI2_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_SPI2_INUM)
#define ESP_SPI3_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_SPI3_INUM)
#define ESP_SPI3_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_SPI3_INUM)
#define ESP_I2S0_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_I2S0_INUM)
#define ESP_I2S0_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_I2S0_INUM)
#define ESP_I2S1_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_I2S1_INUM)
#define ESP_I2S1_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_I2S1_INUM)
#define ESP_MPWM_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_MPWM_INUM)
#define ESP_EPWM_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_EPWM_INUM)
#define ESP_MPWM_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_MPWM_INUM)
#define ESP_EPWM_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_EPWM_INUM)
#define ESP_BB_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_BB_INUM)
#define ESP_BB_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_BB_INUM)
#define ESP_UART0_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_UART0_INUM)
#define ESP_UART0_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_UART0_INUM)
#define ESP_LEDC_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_LEDC_INUM)
#define ESP_LEDC_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_LEDC_INUM)
#define ESP_GPIO_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_GPIO_INUM)
#define ESP_GPIO_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_GPIO_INUM)
#define ESP_WDT_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_WDT_INUM)
#define ESP_WDT_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_WDT_INUM)
#define ESP_FRC1_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_FRC_TIMER1_INUM)
#define ESP_FRC1_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_FRC_TIMER1_INUM)
#define ESP_FRC2_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_FRC_TIMER2_INUM)
#define ESP_FRC2_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_FRC_TIMER2_INUM)
#define ESP_RTC_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_RTC_INUM)
#define ESP_RTC_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_RTC_INUM)
#define ESP_SLC_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_SLC_INUM)
#define ESP_SLC_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_SLC_INUM)
#define ESP_PCNT_INTR_ENABLE() \
ESP_INTR_ENABLE(ETS_PCNT_INUM)
#define ESP_PCNT_INTR_DISABLE() \
ESP_INTR_DISABLE(ETS_PCNT_INUM)
#define ESP_RMT_CTRL_ENABLE() \
ESP_INTR_ENABLE(ETS_RMT_CTRL_INUM)
#define ESP_RMT_CTRL_DIABLE() \
ESP_INTR_DISABLE(ETS_RMT_CTRL_INUM)
#ifdef __cplusplus
}
#endif
......
// 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.
#pragma once
#include <stdint.h>
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @file PHY init parameters and API
*/
/**
* @brief Structure holding PHY init parameters
*/
typedef struct {
uint8_t param_ver_id; /*!< init_data structure version */
uint8_t crystal_select; /*!< 0: 40MHz, 1: 26 MHz, 2: 24 MHz, 3: auto */
uint8_t wifi_rx_gain_swp_step_1; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_2; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_3; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_4; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_5; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_6; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_7; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_8; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_9; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_10; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_11; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_12; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_13; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_14; /*!< do not change */
uint8_t wifi_rx_gain_swp_step_15; /*!< do not change */
uint8_t bt_rx_gain_swp_step_1; /*!< do not change */
uint8_t bt_rx_gain_swp_step_2; /*!< do not change */
uint8_t bt_rx_gain_swp_step_3; /*!< do not change */
uint8_t bt_rx_gain_swp_step_4; /*!< do not change */
uint8_t bt_rx_gain_swp_step_5; /*!< do not change */
uint8_t bt_rx_gain_swp_step_6; /*!< do not change */
uint8_t bt_rx_gain_swp_step_7; /*!< do not change */
uint8_t bt_rx_gain_swp_step_8; /*!< do not change */
uint8_t bt_rx_gain_swp_step_9; /*!< do not change */
uint8_t bt_rx_gain_swp_step_10; /*!< do not change */
uint8_t bt_rx_gain_swp_step_11; /*!< do not change */
uint8_t bt_rx_gain_swp_step_12; /*!< do not change */
uint8_t bt_rx_gain_swp_step_13; /*!< do not change */
uint8_t bt_rx_gain_swp_step_14; /*!< do not change */
uint8_t bt_rx_gain_swp_step_15; /*!< do not change */
uint8_t gain_cmp_1; /*!< do not change */
uint8_t gain_cmp_6; /*!< do not change */
uint8_t gain_cmp_11; /*!< do not change */
uint8_t gain_cmp_ext2_1; /*!< do not change */
uint8_t gain_cmp_ext2_6; /*!< do not change */
uint8_t gain_cmp_ext2_11; /*!< do not change */
uint8_t gain_cmp_ext3_1; /*!< do not change */
uint8_t gain_cmp_ext3_6; /*!< do not change */
uint8_t gain_cmp_ext3_11; /*!< do not change */
uint8_t gain_cmp_bt_ofs_1; /*!< do not change */
uint8_t gain_cmp_bt_ofs_6; /*!< do not change */
uint8_t gain_cmp_bt_ofs_11; /*!< do not change */
uint8_t target_power_qdb_0; /*!< 78 means target power is 78/4=19.5dbm */
uint8_t target_power_qdb_1; /*!< 76 means target power is 76/4=19dbm */
uint8_t target_power_qdb_2; /*!< 74 means target power is 74/4=18.5dbm */
uint8_t target_power_qdb_3; /*!< 68 means target power is 68/4=17dbm */
uint8_t target_power_qdb_4; /*!< 64 means target power is 64/4=16dbm */
uint8_t target_power_qdb_5; /*!< 52 means target power is 52/4=13dbm */
uint8_t target_power_index_mcs0; /*!< target power index is 0, means target power is target_power_qdb_0 19.5dbm; (1m,2m,5.5m,11m,6m,9m) */
uint8_t target_power_index_mcs1; /*!< target power index is 0, means target power is target_power_qdb_0 19.5dbm; (12m) */
uint8_t target_power_index_mcs2; /*!< target power index is 1, means target power is target_power_qdb_1 19dbm; (18m) */
uint8_t target_power_index_mcs3; /*!< target power index is 1, means target power is target_power_qdb_1 19dbm; (24m) */
uint8_t target_power_index_mcs4; /*!< target power index is 2, means target power is target_power_qdb_2 18.5dbm; (36m) */
uint8_t target_power_index_mcs5; /*!< target power index is 3, means target power is target_power_qdb_3 17dbm; (48m) */
uint8_t target_power_index_mcs6; /*!< target power index is 4, means target power is target_power_qdb_4 16dbm; (54m) */
uint8_t target_power_index_mcs7; /*!< target power index is 5, means target power is target_power_qdb_5 13dbm */
uint8_t pwr_ind_11b_en; /*!< 0: 11b power is same as mcs0 and 6m, 1: 11b power different with OFDM */
uint8_t pwr_ind_11b_0; /*!< 1m, 2m power index [0~5] */
uint8_t pwr_ind_11b_1; /*!< 5.5m, 11m power index [0~5] */
uint8_t chan_backoff_en; /*!< 0: channel backoff disable, 1:channel backoff enable */
uint8_t chan1_power_backoff_qdb; /*!< 4 means backoff is 1db */
uint8_t chan2_power_backoff_qdb; /*!< see chan1_power_backoff_qdb */
uint8_t chan3_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan4_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan5_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan6_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan7_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan8_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan9_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan10_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan11_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan12_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan13_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan14_power_backoff_qdb; /*!< chan1_power_backoff_qdb */
uint8_t chan1_rate_backoff_index; /*!< if bit i is set, backoff data rate is target_power_qdb_i */
uint8_t chan2_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan3_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan4_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan5_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan6_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan7_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan8_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan9_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan10_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan11_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan12_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan13_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t chan14_rate_backoff_index; /*!< see chan1_rate_backoff_index */
uint8_t spur_freq_cfg_msb_1; /*!< first spur: */
uint8_t spur_freq_cfg_1; /*!< spur_freq_cfg = (spur_freq_cfg_msb_1 <<8) | spur_freq_cfg_1 */
uint8_t spur_freq_cfg_div_1; /*!< spur_freq=spur_freq_cfg/spur_freq_cfg_div_1 */
uint8_t spur_freq_en_h_1; /*!< the seventh bit for total enable */
uint8_t spur_freq_en_l_1; /*!< each bit for 1 channel, and use [spur_freq_en_h, spur_freq_en_l] to select the spur's channel priority */
uint8_t spur_freq_cfg_msb_2; /*!< second spur: */
uint8_t spur_freq_cfg_2; /*!< spur_freq_cfg = (spur_freq_cfg_msb_2 <<8) | spur_freq_cfg_2 */
uint8_t spur_freq_cfg_div_2; /*!< spur_freq=spur_freq_cfg/spur_freq_cfg_div_2 */
uint8_t spur_freq_en_h_2; /*!< the seventh bit for total enable */
uint8_t spur_freq_en_l_2; /*!< each bit for 1 channel, and use [spur_freq_en_h, spur_freq_en_l] to select the spur's channel priority */
uint8_t spur_freq_cfg_msb_3; /*!< third spur: */
uint8_t spur_freq_cfg_3; /*!< spur_freq_cfg = (spur_freq_cfg_msb_3 <<8) | spur_freq_cfg_3 */
uint8_t spur_freq_cfg_div_3; /*!< spur_freq=spur_freq_cfg/spur_freq_cfg_div_3 */
uint8_t spur_freq_en_h_3; /*!< the seventh bit for total enable */
uint8_t spur_freq_en_l_3; /*!< each bit for 1 channel, and use [spur_freq_en_h, spur_freq_en_l] to select the spur's channel priority, */
uint8_t reserved[23]; /*!< reserved for future expansion */
} esp_phy_init_data_t;
/**
* @brief Opaque PHY calibration data
*/
typedef struct {
uint8_t opaque[1904]; /*!< calibration data */
} esp_phy_calibration_data_t;
typedef enum {
PHY_RF_CAL_PARTIAL = 0x00000000, /*!< Do part of RF calibration. This should be used after power-on reset. */
PHY_RF_CAL_NONE = 0x00000001, /*!< Don't do any RF calibration. This mode is only suggested to be used after deep sleep reset. */
PHY_RF_CAL_FULL = 0x00000002 /*!< Do full RF calibration. Produces best results, but also consumes a lot of time and current. Suggested to be used once. */
} esp_phy_calibration_mode_t;
/**
* @brief Get PHY init data
*
* If "Use a partition to store PHY init data" option is set in menuconfig,
* This function will load PHY init data from a partition. Otherwise,
* PHY init data will be compiled into the application itself, and this function
* will return a pointer to PHY init data located in read-only memory (DROM).
*
* If "Use a partition to store PHY init data" option is enabled, this function
* may return NULL if the data loaded from flash is not valid.
*
* @note Call esp_phy_release_init_data to release the pointer obtained using
* this function after the call to esp_wifi_init.
*
* @return pointer to PHY init data structure
*/
const esp_phy_init_data_t* esp_phy_get_init_data();
/**
* @brief Release PHY init data
* @param data pointer to PHY init data structure obtained from
* esp_phy_get_init_data function
*/
void esp_phy_release_init_data(const esp_phy_init_data_t* data);
/**
* @brief Function called by esp_phy_init to load PHY calibration data
*
* This is a convenience function which can be used to load PHY calibration
* data from NVS. Data can be stored to NVS using esp_phy_store_cal_data_to_nvs
* function.
*
* If calibration data is not present in the NVS, or
* data is not valid (was obtained for a chip with a different MAC address,
* or obtained for a different version of software), this function will
* return an error.
*
* If "Initialize PHY in startup code" option is set in menuconfig, this
* function will be used to load calibration data. To provide a different
* mechanism for loading calibration data, disable
* "Initialize PHY in startup code" option in menuconfig and call esp_phy_init
* function from the application. For an example usage of esp_phy_init and
* this function, see do_phy_init function in cpu_start.c
*
* @param out_cal_data pointer to calibration data structure to be filled with
* loaded data.
* @return ESP_OK on success
*/
esp_err_t esp_phy_load_cal_data_from_nvs(esp_phy_calibration_data_t* out_cal_data);
/**
* @brief Function called by esp_phy_init to store PHY calibration data
*
* This is a convenience function which can be used to store PHY calibration
* data to the NVS. Calibration data is returned by esp_phy_init function.
* Data saved using this function to the NVS can later be loaded using
* esp_phy_store_cal_data_to_nvs function.
*
* If "Initialize PHY in startup code" option is set in menuconfig, this
* function will be used to store calibration data. To provide a different
* mechanism for storing calibration data, disable
* "Initialize PHY in startup code" option in menuconfig and call esp_phy_init
* function from the application.
*
* @param cal_data pointer to calibration data which has to be saved.
* @return ESP_OK on success
*/
esp_err_t esp_phy_store_cal_data_to_nvs(const esp_phy_calibration_data_t* cal_data);
/**
* @brief Initialize PHY module
*
* PHY module should be initialized in order to use WiFi or BT.
* If "Initialize PHY in startup code" option is set in menuconfig,
* this function will be called automatically before app_main is called,
* using parameters obtained from esp_phy_get_init_data.
*
* Applications which don't need to enable PHY on every start up should
* disable this menuconfig option and call esp_phy_init before calling
* esp_wifi_init or bt_controller_init. See do_phy_init function in
* cpu_start.c for an example of using this function.
*
* @param init_data PHY parameters. Default set of parameters can
* be obtained by calling esp_phy_get_default_init_data
* function.
* @param mode Calibration mode (Full, partial, or no calibration)
* @param[inout] calibration_data
* @return ESP_OK on success.
*/
esp_err_t esp_phy_init(const esp_phy_init_data_t* init_data,
esp_phy_calibration_mode_t mode, esp_phy_calibration_data_t* calibration_data);
#ifdef __cplusplus
}
#endif
......@@ -16,7 +16,7 @@
#define __ESP_SYSTEM_H__
#include <stdint.h>
#include <stdbool.h>
#include "esp_err.h"
#include "esp_deepsleep.h"
......@@ -24,166 +24,107 @@
extern "C" {
#endif
/** \defgroup System_APIs System APIs
* @brief System APIs
*/
/** @addtogroup System_APIs
* @{
*/
/**
* @attention application don't need to call this function anymore. It do nothing and will
* be removed in future version.
*/
void system_init(void) __attribute__ ((deprecated));
/**
* @brief Get information of the SDK version.
*
* @param null
* @brief Reset to default settings.
*
* @return Information of the SDK version.
* Function has been deprecated, please use esp_wifi_restore instead.
* This name will be removed in a future release.
*/
const char *system_get_sdk_version(void);
void system_restore(void) __attribute__ ((deprecated));
/**
* @brief Reset to default settings.
*
* Reset to default settings of the following APIs : wifi_station_set_auto_connect,
* wifi_set_phy_mode, wifi_softap_set_config related, wifi_station_set_config
* related, and wifi_set_opmode.
*
* @param null
* @brief Restart PRO and APP CPUs.
*
* @return null
* This function can be called both from PRO and APP CPUs.
* After successful restart, CPU reset reason will be SW_CPU_RESET.
* Peripherals (except for WiFi, BT, UART0, SPI1, and legacy timers) are not reset.
* This function does not return.
*/
void system_restore(void);
void esp_restart(void) __attribute__ ((noreturn));
/**
* @brief Restart system.
*
* @param null
*
* @return null
* Function has been renamed to esp_restart.
* This name will be removed in a future release.
*/
void system_restart(void);
void system_restart(void) __attribute__ ((deprecated, noreturn));
/**
* @brief Get system time, unit: microsecond.
*
* @param null
*
* @return System time, unit: microsecond.
* This function is deprecated. Use 'gettimeofday' function for 64-bit precision.
* This definition will be removed in a future release.
*/
uint32_t system_get_time(void);
uint32_t system_get_time(void) __attribute__ ((deprecated));
/**
* @brief Get the size of available heap.
*
* @param null
*
* @return Available heap size.
*/
uint32_t system_get_free_heap_size(void);
/**
* @brief Get RTC time, unit: RTC clock cycle.
*
* @param null
* Note that the returned value may be larger than the maximum contiguous block
* which can be allocated.
*
* @return RTC time.
* @return Available heap size, in bytes.
*/
uint64_t system_get_rtc_time(void);
uint32_t esp_get_free_heap_size(void);
/**
* @brief Read user data from the RTC memory.
*
* The user data segment (1024 bytes, as shown below) is used to store user data.
*
* |<---- system data(512 bytes) ---->|<----------- user data(1024 bytes) --------->|
*
* @attention Read and write unit for data stored in the RTC memory is 4 bytes.
* @attention src_addr is the block number (4 bytes per block). So when reading data
* at the beginning of the user data segment, src_addr will be 512/4 = 128,
* n will be data length.
* @brief Get the size of available heap.
*
* @param uint16 src : source address of rtc memory, src_addr >= 128
* @param void *dst : data pointer
* @param uint16 n : data length, unit: byte
* Function has been renamed to esp_get_free_heap_size.
* This name will be removed in a future release.
*
* @return true : succeed
* @return false : fail
* @return Available heap size, in bytes.
*/
bool system_rtc_mem_read(uint16_t src, void *dst, uint16_t n);
uint32_t system_get_free_heap_size(void) __attribute__ ((deprecated));
/**
* @brief Write user data to the RTC memory.
*
* During deep-sleep, only RTC is working. So users can store their data
* in RTC memory if it is needed. The user data segment below (1024 bytes)
* is used to store the user data.
*
* |<---- system data(512 bytes) ---->|<----------- user data(1024 bytes) --------->|
*
* @attention Read and write unit for data stored in the RTC memory is 4 bytes.
* @attention src_addr is the block number (4 bytes per block). So when storing data
* at the beginning of the user data segment, src_addr will be 512/4 = 128,
* n will be data length.
*
* @param uint16 src : source address of rtc memory, src_addr >= 128
* @param void *dst : data pointer
* @param uint16 n : data length, unit: byte
*
* @return true : succeed
* @return false : fail
*/
bool system_rtc_mem_write(uint16_t dst, const void *src, uint16_t n);
/** \defgroup System_boot_APIs Boot APIs
* @brief boot APIs
*/
/** @addtogroup System_boot_APIs
* @{
*/
* @brief Get one random 32-bit word from hardware RNG
*
* @return random value between 0 and UINT32_MAX
*/
uint32_t esp_random(void);
/**
* @}
*/
/** \defgroup Hardware_MAC_APIs Hardware MAC APIs
* @brief Hardware MAC address APIs
* @brief Read hardware MAC address.
*
* In WiFi MAC, only ESP32 station MAC is the hardware MAC, ESP32 softAP MAC is a software MAC
* calculated from ESP32 station MAC.
* So users need to call wifi_get_macaddr to query the ESP32 softAP MAC if ESP32 station MAC changed.
* So users need to call esp_wifi_get_macaddr to query the ESP32 softAP MAC if ESP32 station MAC changed.
*
* @param mac hardware MAC address, length: 6 bytes.
*
* @return ESP_OK on success
*/
/** @addtogroup Hardware_MAC_APIs
* @{
*/
esp_err_t esp_efuse_read_mac(uint8_t* mac);
/**
* @brief Read hardware MAC address.
*
* @param uint8 mac[6] : the hardware MAC address, length: 6 bytes.
* Function has been renamed to esp_efuse_read_mac.
* This name will be removed in a future release.
*
* @return esp_err_t
* @param mac hardware MAC address, length: 6 bytes.
* @return ESP_OK on success
*/
esp_err_t system_efuse_read_mac(uint8_t mac[6]);
esp_err_t system_efuse_read_mac(uint8_t mac[6]) __attribute__ ((deprecated));
/**
* @}
*/
* Get SDK version
*
* This function is deprecated and will be removed in a future release.
*
* @return constant string "master"
*/
const char* system_get_sdk_version(void) __attribute__ ((deprecated));
/**
* @}
*/
#ifdef __cplusplus
}
......
......@@ -22,52 +22,4 @@
#include <stdbool.h>
#include <stddef.h>
#define __ATTRIB_PACK __attribute__ ((packed))
#define __ATTRIB_PRINTF __attribute__ ((format (printf, 1, 2)))
#define __ATTRIB_NORETURN __attribute__ ((noreturn))
#define __ATTRIB_ALIGN(x) __attribute__ ((aligned((x))))
#define INLINE __inline__
#define LOCAL static
/* probably should not put STATUS here */
typedef enum {
OK = 0,
FAIL,
PENDING,
BUSY,
CANCEL,
} STATUS;
//#define _LITTLE_ENDIAN 1234
//#define _BYTE_ORDER == _LITTLE_ENDIAN
#define ASSERT( x ) do { \
if (!(x)) { \
printf("%s %u\n", __FILE__, __LINE__); \
while (1) { \
asm volatile("nop"); \
}; \
} \
} while (0)
/* #if __GNUC_PREREQ__(4, 1) */
#ifndef __GNUC__
#if 1
#define __offsetof(type, field) __builtin_offsetof(type, field)
#else
#define __offsetof(type, field) ((size_t)(&((type *)0)->field))
#endif
#endif /* __GNUC__ */
/* Macros for counting and rounding. */
#ifndef howmany
#define howmany(x, y) (((x)+((y)-1))/(y))
#endif
#define container_of(ptr, type, member) ({ \
const typeof( ((type *)0)->member ) *__mptr = (ptr); \
(type *)( (char *)__mptr - __offsetof(type,member) );})
#endif /* __ESP_TYPES_H__ */
......@@ -186,6 +186,21 @@ esp_err_t esp_wifi_start(void);
*/
esp_err_t esp_wifi_stop(void);
/**
* @brief Restore WiFi stack persistent settings to default values
*
* This function will reset settings made using the following APIs:
* - esp_wifi_get_auto_connect,
* - esp_wifi_set_protocol,
* - esp_wifi_set_config related
* - esp_wifi_set_mode
*
* @return
* - ESP_OK: succeed
* - ESP_ERR_WIFI_NOT_INIT: WiFi is not initialized by eps_wifi_init
*/
esp_err_t esp_wifi_restore(void);
/**
* @brief Connect the ESP32 WiFi station to the AP.
*
......
......@@ -43,10 +43,9 @@ extern "C" {
/**
* @brief get whether the wifi driver is allowed to transmit data or not
*
* @param none
*
* @return true : upper layer should stop to transmit data to wifi driver
* @return false : upper layer can transmit data to wifi driver
* @return
* - true : upper layer should stop to transmit data to wifi driver
* - false : upper layer can transmit data to wifi driver
*/
bool esp_wifi_internal_tx_is_stop(void);
......@@ -54,8 +53,6 @@ bool esp_wifi_internal_tx_is_stop(void);
* @brief free the rx buffer which allocated by wifi driver
*
* @param void* buffer: rx buffer pointer
*
* @return nonoe
*/
void esp_wifi_internal_free_rx_buffer(void* buffer);
......@@ -78,7 +75,6 @@ int esp_wifi_internal_tx(wifi_interface_t wifi_if, void *buffer, u16_t len);
* @brief The WiFi RX callback function
*
* Each time the WiFi need to forward the packets to high layer, the callback function will be called
*
*/
typedef esp_err_t (*wifi_rxcb_t)(void *buffer, uint16_t len, void *eb);
......@@ -90,18 +86,18 @@ typedef esp_err_t (*wifi_rxcb_t)(void *buffer, uint16_t len, void *eb);
* @param wifi_interface_t ifx : interface
* @param wifi_rxcb_t fn : WiFi RX callback
*
* @return ESP_OK : succeed
* @return others : fail
* @return
* - ESP_OK : succeed
* - others : fail
*/
esp_err_t esp_wifi_internal_reg_rxcb(wifi_interface_t ifx, wifi_rxcb_t fn);
/**
* @brief Notify WIFI driver that the station got ip successfully
*
* @param none
*
* @return ESP_OK : succeed
* @return others : fail
* @return
* - ESP_OK : succeed
* - others : fail
*/
esp_err_t esp_wifi_internal_set_sta_ip(void);
......
......@@ -605,6 +605,14 @@ void intr_matrix_set(int cpu_no, uint32_t model_num, uint32_t intr_num);
#define ETS_MEM_BAR() asm volatile ( "" : : : "memory" )
typedef enum {
OK = 0,
FAIL,
PENDING,
BUSY,
CANCEL,
} STATUS;
/**
* @}
*/
......
......@@ -17,6 +17,7 @@
#include "esp_types.h"
#include "esp_attr.h"
#include "ets_sys.h"
#ifdef __cplusplus
extern "C" {
......
......@@ -51,7 +51,10 @@ static inline void cpu_write_itlb(unsigned vpn, unsigned attr)
asm volatile ("witlb %1, %0; isync\n" :: "r" (vpn), "r" (attr));
}
/* Make page 0 access raise an exception.
/**
* @brief Configure memory region protection
*
* Make page 0 access raise an exception.
* Also protect some other unused pages so we can catch weirdness.
* Useful attribute values:
* 0 — cached, RW
......@@ -70,9 +73,7 @@ static inline void cpu_configure_region_protection()
cpu_write_itlb(0x20000000, 0);
}
/*
/**
* @brief Set CPU frequency to the value defined in menuconfig
*
* Called from cpu_start.c, not intended to be called from other places.
......@@ -81,4 +82,16 @@ static inline void cpu_configure_region_protection()
*/
void esp_set_cpu_freq(void);
/**
* @brief Stall CPU using RTC controller
* @param cpu_id ID of the CPU to stall (0 = PRO, 1 = APP)
*/
void esp_cpu_stall(int cpu_id);
/**
* @brief Un-stall CPU using RTC controller
* @param cpu_id ID of the CPU to un-stall (0 = PRO, 1 = APP)
*/
void esp_cpu_unstall(int cpu_id);
#endif
......@@ -1028,6 +1028,7 @@
#define DPORT_WIFI_RST_EN_REG (DR_REG_DPORT_BASE + 0x0D0)
/* DPORT_WIFI_RST : R/W ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define DPORT_MAC_RST (BIT(2))
#define DPORT_WIFI_RST 0xFFFFFFFF
#define DPORT_WIFI_RST_M ((DPORT_WIFI_RST_V)<<(DPORT_WIFI_RST_S))
#define DPORT_WIFI_RST_V 0xFFFFFFFF
......
// 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 __HWCRYPTO_REG_H__
#define __HWCRYPTO_REG_H__
#include "soc.h"
/* registers for RSA acceleration via Multiple Precision Integer ops */
#define RSA_MEM_M_BLOCK_BASE ((DR_REG_RSA_BASE)+0x000)
/* RB & Z use the same memory block, depending on phase of operation */
#define RSA_MEM_RB_BLOCK_BASE ((DR_REG_RSA_BASE)+0x200)
#define RSA_MEM_Z_BLOCK_BASE ((DR_REG_RSA_BASE)+0x200)
#define RSA_MEM_Y_BLOCK_BASE ((DR_REG_RSA_BASE)+0x400)
#define RSA_MEM_X_BLOCK_BASE ((DR_REG_RSA_BASE)+0x600)
#define RSA_M_DASH_REG (DR_REG_RSA_BASE + 0x800)
#define RSA_MODEXP_MODE_REG (DR_REG_RSA_BASE + 0x804)
#define RSA_START_MODEXP_REG (DR_REG_RSA_BASE + 0x808)
#define RSA_MULT_MODE_REG (DR_REG_RSA_BASE + 0x80c)
#define RSA_MULT_START_REG (DR_REG_RSA_BASE + 0x810)
#define RSA_INTERRUPT_REG (DR_REG_RSA_BASE + 0X814)
#define RSA_CLEAN_ADDR (DR_REG_RSA_BASE + 0X818)
#endif
......@@ -1319,6 +1319,36 @@
#define PCNT_CORE_STATUS_U0_M ((PCNT_CORE_STATUS_U0_V)<<(PCNT_CORE_STATUS_U0_S))
#define PCNT_CORE_STATUS_U0_V 0xFFFFFFFF
#define PCNT_CORE_STATUS_U0_S 0
/*0: positive value to zero; 1: negative value to zero; 2: counter value negative ; 3: counter value positive*/
#define PCNT_STATUS_CNT_MODE 0x3
#define PCNT_STATUS_CNT_MODE_M ((PCNT_STATUS_CNT_MODE_V)<<(PCNT_STATUS_CNT_MODE_S))
#define PCNT_STATUS_CNT_MODE_V 0x3
#define PCNT_STATUS_CNT_MODE_S 0
/* counter value equals to thresh1*/
#define PCNT_STATUS_THRES1 BIT(2)
#define PCNT_STATUS_THRES1_M BIT(2)
#define PCNT_STATUS_THRES1_V 0x1
#define PCNT_STATUS_THRES1_S 2
/* counter value equals to thresh0*/
#define PCNT_STATUS_THRES0 BIT(3)
#define PCNT_STATUS_THRES0_M BIT(3)
#define PCNT_STATUS_THRES0_V 0x1
#define PCNT_STATUS_THRES0_S 3
/* counter value reaches h_lim*/
#define PCNT_STATUS_L_LIM BIT(4)
#define PCNT_STATUS_L_LIM_M BIT(4)
#define PCNT_STATUS_L_LIM_V 0x1
#define PCNT_STATUS_L_LIM_S 4
/* counter value reaches l_lim*/
#define PCNT_STATUS_H_LIM BIT(5)
#define PCNT_STATUS_H_LIM_M BIT(5)
#define PCNT_STATUS_H_LIM_V 0x1
#define PCNT_STATUS_H_LIM_S 5
/* counter value equals to zero*/
#define PCNT_STATUS_ZERO BIT(6)
#define PCNT_STATUS_ZERO_M BIT(6)
#define PCNT_STATUS_ZERO_V 0x1
#define PCNT_STATUS_ZERO_S 6
#define PCNT_U1_STATUS_REG (DR_REG_PCNT_BASE + 0x0094)
/* PCNT_CORE_STATUS_U1 : RO ;bitpos:[31:0] ;default: 32'h0 ; */
......
......@@ -113,7 +113,18 @@ typedef volatile struct {
};
uint32_t val;
} int_clr;
uint32_t status_unit[8];
union {
struct {
uint32_t cnt_mode:2; /*0: positive value to zero; 1: negative value to zero; 2: counter value negative ; 3: counter value positive*/
uint32_t thres1_lat:1; /* counter value equals to thresh1*/
uint32_t thres0_lat:1; /* counter value equals to thresh0*/
uint32_t l_lim_lat:1; /* counter value reaches h_lim*/
uint32_t h_lim_lat:1; /* counter value reaches l_lim*/
uint32_t zero_lat:1; /* counter value equals zero*/
uint32_t reserved7:25;
};
uint32_t val;
} status_unit[8];
union {
struct {
uint32_t cnt_rst_u0: 1; /*Set this bit to clear unit0's counter.*/
......
......@@ -2163,7 +2163,8 @@
#define RMT_DATE_V 0xFFFFFFFF
#define RMT_DATE_S 0
/* RMT memory block address */
#define RMT_CHANNEL_MEM(i) (DR_REG_RMT_BASE + 0x800 + 64 * 4 * (i))
#endif /*_SOC_RMT_REG_H_ */
......
......@@ -226,18 +226,35 @@ typedef volatile struct {
} rmt_dev_t;
extern rmt_dev_t RMT;
//Allow access to RMT memory using RMTMEM.chan[0].data[8]
typedef struct {
union {
struct {
uint32_t duration0 :15;
uint32_t level0 :1;
uint32_t duration1 :15;
uint32_t level1 :1;
};
uint32_t val;
};
} rmt_item32_t;
typedef struct {
union {
struct {
uint16_t duration :15;
uint16_t level :1;
};
uint16_t val;
};
} rmt_item16_t;
//Allow access to RMT memory using RMTMEM.chan[0].data32[8]
typedef volatile struct {
struct {
union {
struct {
uint32_t duration0: 15;
uint32_t level0: 1;
uint32_t duration1: 15;
uint32_t level1: 1;
};
uint32_t val;
} data[64];
rmt_item32_t data32[64];
rmt_item16_t data16[128];
};
} chan[8];
} rmt_mem_t;
extern rmt_mem_t RMTMEM;
......
......@@ -129,10 +129,10 @@
//}}
//Periheral Clock {{
#define APB_CLK_FREQ_ROM 26*1000000
#define APB_CLK_FREQ_ROM ( 26*1000000 )
#define CPU_CLK_FREQ_ROM APB_CLK_FREQ_ROM
#define CPU_CLK_FREQ APB_CLK_FREQ
#define APB_CLK_FREQ 80*1000000 //unit: Hz
#define APB_CLK_FREQ ( 80*1000000 ) //unit: Hz
#define UART_CLK_FREQ APB_CLK_FREQ
#define WDT_CLK_FREQ APB_CLK_FREQ
#define TIMER_CLK_FREQ (80000000>>4) //80MHz divided by 16
......@@ -141,6 +141,7 @@
//}}
#define DR_REG_DPORT_BASE 0x3ff00000
#define DR_REG_RSA_BASE 0x3ff02000
#define DR_REG_UART_BASE 0x3ff40000
#define DR_REG_SPI1_BASE 0x3ff42000
#define DR_REG_SPI0_BASE 0x3ff43000
......
// 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
/* Hardware random number generator register */
#define WDEV_RND_REG 0x60035144
......@@ -42,7 +42,7 @@
* share the name with the existing functions from hal.h.
* Including this header file will define XTHAL_USE_CACHE_MACROS
* which directs hal.h not to use the functions.
*
*/
/*
* Single-cache-line operations in C-callable inline assembly.
......
......@@ -895,7 +895,8 @@ typedef struct xSTATIC_TCB
uint32_t ulDummy18;
uint32_t ucDummy19;
#endif
#if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) )
#if( ( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) \
|| ( portUSING_MPU_WRAPPERS == 1 ) )
uint8_t uxDummy20;
#endif
......@@ -927,7 +928,6 @@ typedef struct xSTATIC_QUEUE
StaticList_t xDummy3[ 2 ];
UBaseType_t uxDummy4[ 3 ];
BaseType_t ucDummy5[ 2 ];
#if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) )
uint8_t ucDummy6;
......@@ -943,12 +943,12 @@ typedef struct xSTATIC_QUEUE
#endif
struct {
volatile uint32_t mux;
volatile uint32_t ucDummy10;
#ifdef CONFIG_FREERTOS_PORTMUX_DEBUG
const char *lastLockedFn;
int lastLockedLine;
void *pvDummy8;
UBaseType_t uxDummy11;
#endif
} mux;
} sDummy12;
} StaticQueue_t;
typedef StaticQueue_t StaticSemaphore_t;
......
......@@ -108,6 +108,7 @@
/* configASSERT behaviour */
#ifndef __ASSEMBLER__
#include <stdlib.h> /* for abort() */
#include "rom/ets_sys.h"
#if defined(CONFIG_FREERTOS_ASSERT_DISABLE)
......@@ -126,8 +127,6 @@
#endif
#if CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION
#include <stdlib.h>
#include "rom/ets_sys.h"
#define UNTESTED_FUNCTION() { ets_printf("Untested FreeRTOS function %s\r\n", __FUNCTION__); configASSERT(false); } while(0)
#else
#define UNTESTED_FUNCTION()
......
......@@ -190,6 +190,10 @@ struct xLIST_ITEM
};
typedef struct xLIST_ITEM ListItem_t; /* For some reason lint wants this as two separate definitions. */
#if __GNUC_PREREQ(4, 6)
_Static_assert(sizeof(StaticListItem_t) == sizeof(ListItem_t), "StaticListItem_t != ListItem_t");
#endif
struct xMINI_LIST_ITEM
{
listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
......@@ -199,6 +203,11 @@ struct xMINI_LIST_ITEM
};
typedef struct xMINI_LIST_ITEM MiniListItem_t;
#if __GNUC_PREREQ(4, 6)
_Static_assert(sizeof(StaticMiniListItem_t) == sizeof(MiniListItem_t), "StaticMiniListItem_t != MiniListItem_t");
#endif
/*
* Definition of the type of queue used by the scheduler.
*/
......@@ -211,6 +220,10 @@ typedef struct xLIST
listSECOND_LIST_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
} List_t;
#if __GNUC_PREREQ(4, 6)
_Static_assert(sizeof(StaticList_t) == sizeof(List_t), "StaticList_t != List_t");
#endif
/*
* Access macro to set the owner of a list item. The owner of a list item
* is the object (usually a TCB) that contains the list item.
......
......@@ -18,10 +18,7 @@
#include <stdint.h>
#include <stdarg.h>
#include "sdkconfig.h"
#ifdef BOOTLOADER_BUILD
#include <rom/ets_sys.h>
#endif
#ifdef __cplusplus
extern "C" {
......
......@@ -68,8 +68,13 @@ extern "C" {
#define ANNOUNCE_NUM 2 /* (number of announcement packets) */
#define ANNOUNCE_INTERVAL 2 /* seconds (time between announcement packets) */
#define ANNOUNCE_WAIT 2 /* seconds (delay before announcing) */
#if CONFIG_MDNS
#define MAX_CONFLICTS 9 /* (max conflicts before rate limiting) */
#define RATE_LIMIT_INTERVAL 20 /* seconds (delay between successive attempts) */
#else
#define MAX_CONFLICTS 10 /* (max conflicts before rate limiting) */
#define RATE_LIMIT_INTERVAL 60 /* seconds (delay between successive attempts) */
#endif
#define DEFEND_INTERVAL 10 /* seconds (min. wait between defensive ARPs) */
/* AutoIP client states */
......
......@@ -352,6 +352,10 @@ err_t nd6_queue_packet(s8_t neighbor_index, struct pbuf * p);
void nd6_reachability_hint(const ip6_addr_t * ip6addr);
#endif /* LWIP_ND6_TCP_REACHABILITY_HINTS */
#if ESP_LWIP
/** set nd6 callback when ipv6 addr state pref*/
void nd6_set_cb(struct netif *netif, void (*cb)(struct netif *netif, u8_t ip_index));
#endif
#ifdef __cplusplus
}
#endif
......
......@@ -190,11 +190,6 @@ struct netif {
/** pointer to next in linked list */
struct netif *next;
#if ESP_LWIP
//ip_addr_t is changed by marco IPV4, IPV6
ip_addr_t link_local_addr;
#endif
#if LWIP_IPV4
/** IP address configuration in network byte order */
ip_addr_t ip_addr;
......@@ -207,6 +202,10 @@ struct netif {
/** The state of each IPv6 address (Tentative, Preferred, etc).
* @see ip6_addr.h */
u8_t ip6_addr_state[LWIP_IPV6_NUM_ADDRESSES];
#if ESP_LWIP
void (*ipv6_addr_cb)(struct netif* netif, u8_t ip_idex); /* callback for ipv6 addr states changed */
#endif
#endif /* LWIP_IPV6 */
/** This function is called by the network device driver
* to pass a packet up the TCP/IP stack. */
......
......@@ -65,8 +65,8 @@
*/
#define SMEMCPY(dst,src,len) memcpy(dst,src,len)
extern unsigned long os_random(void);
#define LWIP_RAND rand
#define LWIP_RAND rand
/*
------------------------------------
---------- Memory options ----------
......@@ -200,13 +200,35 @@ extern unsigned long os_random(void);
*/
#define LWIP_DHCP 1
#define DHCP_MAXRTX 0
#define DHCP_MAXRTX 0 //(*(volatile uint32*)0x600011E0)
/*
------------------------------------
---------- AUTOIP options ----------
------------------------------------
*/
#if CONFIG_MDNS
/**
* LWIP_AUTOIP==1: Enable AUTOIP module.
*/
#define LWIP_AUTOIP 1
/**
* LWIP_DHCP_AUTOIP_COOP==1: Allow DHCP and AUTOIP to be both enabled on
* the same interface at the same time.
*/
#define LWIP_DHCP_AUTOIP_COOP 1
/**
* LWIP_DHCP_AUTOIP_COOP_TRIES: Set to the number of DHCP DISCOVER probes
* that should be sent before falling back on AUTOIP. This can be set
* as low as 1 to get an AutoIP address very quickly, but you should
* be prepared to handle a changing IP address when DHCP overrides
* AutoIP.
*/
#define LWIP_DHCP_AUTOIP_COOP_TRIES 2
#endif
/*
----------------------------------
---------- SNMP options ----------
......@@ -308,6 +330,19 @@ extern unsigned long os_random(void);
---------- LOOPIF options ----------
------------------------------------
*/
#if CONFIG_MDNS
/**
* LWIP_NETIF_LOOPBACK==1: Support sending packets with a destination IP
* address equal to the netif IP address, looping them back up the stack.
*/
#define LWIP_NETIF_LOOPBACK 1
/**
* LWIP_LOOPBACK_MAX_PBUFS: Maximum number of pbufs on queue for loopback
* sending for each netif (0 = disabled)
*/
#define LWIP_LOOPBACK_MAX_PBUFS 8
#endif
/*
------------------------------------
......@@ -414,6 +449,15 @@ extern unsigned long os_random(void);
*/
#define SO_REUSE CONFIG_LWIP_SO_REUSE
#if CONFIG_MDNS
/**
* SO_REUSE_RXTOALL==1: Pass a copy of incoming broadcast/multicast packets
* to all local matches if SO_REUSEADDR is turned on.
* WARNING: Adds a memcpy for every packet if passing to more than one pcb!
*/
#define SO_REUSE_RXTOALL 1
#endif
/*
----------------------------------------
---------- Statistics options ----------
......@@ -515,6 +559,7 @@ extern unsigned long os_random(void);
/* Enable all Espressif-only options */
#define ESP_LWIP 1
#define ESP_LWIP_ARP 1
#define ESP_PER_SOC_TCP_WND 1
#define ESP_THREAD_SAFE 1
#define ESP_THREAD_SAFE_DEBUG LWIP_DBG_OFF
......
......@@ -65,8 +65,8 @@
*/
#define SMEMCPY(dst,src,len) memcpy(dst,src,len)
extern unsigned long os_random(void);
#define LWIP_RAND rand
#define LWIP_RAND rand
/*
------------------------------------
---------- Memory options ----------
......@@ -200,13 +200,35 @@ extern unsigned long os_random(void);
*/
#define LWIP_DHCP 1
#define DHCP_MAXRTX 0
#define DHCP_MAXRTX 0 //(*(volatile uint32*)0x600011E0)
/*
------------------------------------
---------- AUTOIP options ----------
------------------------------------
*/
#if CONFIG_MDNS
/**
* LWIP_AUTOIP==1: Enable AUTOIP module.
*/
#define LWIP_AUTOIP 1
/**
* LWIP_DHCP_AUTOIP_COOP==1: Allow DHCP and AUTOIP to be both enabled on
* the same interface at the same time.
*/
#define LWIP_DHCP_AUTOIP_COOP 1
/**
* LWIP_DHCP_AUTOIP_COOP_TRIES: Set to the number of DHCP DISCOVER probes
* that should be sent before falling back on AUTOIP. This can be set
* as low as 1 to get an AutoIP address very quickly, but you should
* be prepared to handle a changing IP address when DHCP overrides
* AutoIP.
*/
#define LWIP_DHCP_AUTOIP_COOP_TRIES 2
#endif
/*
----------------------------------
---------- SNMP options ----------
......@@ -308,6 +330,19 @@ extern unsigned long os_random(void);
---------- LOOPIF options ----------
------------------------------------
*/
#if CONFIG_MDNS
/**
* LWIP_NETIF_LOOPBACK==1: Support sending packets with a destination IP
* address equal to the netif IP address, looping them back up the stack.
*/
#define LWIP_NETIF_LOOPBACK 1
/**
* LWIP_LOOPBACK_MAX_PBUFS: Maximum number of pbufs on queue for loopback
* sending for each netif (0 = disabled)
*/
#define LWIP_LOOPBACK_MAX_PBUFS 8
#endif
/*
------------------------------------
......@@ -414,6 +449,15 @@ extern unsigned long os_random(void);
*/
#define SO_REUSE CONFIG_LWIP_SO_REUSE
#if CONFIG_MDNS
/**
* SO_REUSE_RXTOALL==1: Pass a copy of incoming broadcast/multicast packets
* to all local matches if SO_REUSEADDR is turned on.
* WARNING: Adds a memcpy for every packet if passing to more than one pcb!
*/
#define SO_REUSE_RXTOALL 1
#endif
/*
----------------------------------------
---------- Statistics options ----------
......@@ -515,6 +559,7 @@ extern unsigned long os_random(void);
/* Enable all Espressif-only options */
#define ESP_LWIP 1
#define ESP_LWIP_ARP 1
#define ESP_PER_SOC_TCP_WND 1
#define ESP_THREAD_SAFE 1
#define ESP_THREAD_SAFE_DEBUG LWIP_DBG_OFF
......
......@@ -20,7 +20,6 @@
*
*
*/
#ifndef AES_ALT_H
#define AES_ALT_H
......@@ -56,4 +55,4 @@ typedef esp_aes_context mbedtls_aes_context;
}
#endif
#endif /* aes.h */
#endif
......@@ -239,7 +239,9 @@
/* The following units have ESP32 hardware support,
uncommenting each _ALT macro will use the
hardware-accelerated implementation. */
#ifdef CONFIG_MBEDTLS_HARDWARE_AES
#define MBEDTLS_AES_ALT
#endif
/* Currently hardware SHA does not work with TLS handshake,
due to concurrency issue. Internal TW#7111. */
......@@ -250,11 +252,11 @@
/* The following MPI (bignum) functions have ESP32 hardware support,
Uncommenting these macros will use the hardware-accelerated
implementations.
Disabled as number of limbs limited by bug. Internal TW#7112.
*/
//#define MBEDTLS_MPI_EXP_MOD_ALT
//#define MBEDTLS_MPI_MUL_MPI_ALT
#ifdef CONFIG_MBEDTLS_HARDWARE_MPI
#define MBEDTLS_MPI_EXP_MOD_ALT
#define MBEDTLS_MPI_MUL_MPI_ALT
#endif
/**
* \def MBEDTLS_MD2_PROCESS_ALT
......
/*
* copyright (c) 2010 - 2012 Espressif System
*
*/
// 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 _SHA1_ALT_H_
#define _SHA1_ALT_H_
......
/*
* copyright (c) 2010 - 2012 Espressif System
*
*/
// 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 _SHA256_ALT_H_
#define _SHA256_ALT_H_
......@@ -30,4 +38,4 @@ typedef esp_sha_context mbedtls_sha256_context;
}
#endif
#endif /* sha256.h */
#endif
/*
* copyright (c) 2010 - 2012 Espressif System
*
* esf Link List Descriptor
*/
// 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 _SHA512_ALT_H_
#define _SHA512_ALT_H_
......@@ -30,4 +37,4 @@ typedef esp_sha_context mbedtls_sha512_context;
}
#endif
#endif /* sha512.h */
#endif
......@@ -18,27 +18,13 @@
extern "C" {
#endif
/** Initialise NVS flash storage with default flash sector layout
Temporarily, this region is hardcoded as a 12KB (0x3000 byte)
region starting at 36KB (0x9000 byte) offset in flash.
@return ESP_OK if flash was successfully initialised.
*/
/**
* @brief Initialize NVS flash storage with layout given in the partition table.
*
* @return ESP_OK if storage was successfully initialized.
*/
esp_err_t nvs_flash_init(void);
/** Initialise NVS flash storage with custom flash sector layout
@param baseSector Flash sector (units of 4096 bytes) offset to start NVS.
@param sectorCount Length (in flash sectors) of NVS region.
@return ESP_OK if flash was successfully initialised.
@note Use this parameter if you're not using the options in menuconfig for
configuring flash layout & partition table.
*/
esp_err_t nvs_flash_init_custom(uint32_t baseSector, uint32_t sectorCount);
#ifdef __cplusplus
}
......
......@@ -55,16 +55,17 @@
#else
#ifdef SSL_PRINT_LOG
#undef SSL_PRINT_LOG
#define SSL_PRINT_LOG(...)
#endif
#define SSL_PRINT_LOG(...)
#ifdef SSL_ERROR_LOG
#undef SSL_ERROR_LOG
#define SSL_ERROR_LOG(...)
#endif
#define SSL_ERROR_LOG(...)
#ifdef SSL_LOCAL_LOG
#undef SSL_LOCAL_LOG
#define SSL_LOCAL_LOG(...)
#endif
#define SSL_LOCAL_LOG(...)
#endif
#if SSL_DEBUG_LOCATION_ENABLE
......
......@@ -76,6 +76,8 @@ esp_err_t spi_flash_erase_range(size_t start_address, size_t size);
*
* @note Address in flash, dest, has to be 4-byte aligned.
* This is a temporary limitation which will be removed.
* @note If source address is in DROM, this function will return
* ESP_ERR_INVALID_ARG.
*
* @param dest destination address in Flash
* @param src pointer to the source buffer
......
......@@ -64,18 +64,22 @@ typedef struct {
ip4_addr_t gw;
} tcpip_adapter_ip_info_t;
typedef struct {
ip6_addr_t ip;
} tcpip_adapter_ip6_info_t;
typedef dhcps_lease_t tcpip_adapter_dhcps_lease_t;
#if CONFIG_DHCP_STA_LIST
typedef struct {
uint8_t mac[6];
ip4_addr_t ip;
}tcpip_adapter_sta_info_t;
} tcpip_adapter_sta_info_t;
typedef struct {
tcpip_adapter_sta_info_t sta[ESP_WIFI_MAX_CONN_NUM];
int num;
}tcpip_adapter_sta_list_t;
} tcpip_adapter_sta_list_t;
#endif
#endif
......@@ -211,6 +215,35 @@ esp_err_t tcpip_adapter_get_ip_info(tcpip_adapter_if_t tcpip_if, tcpip_adapter_i
*/
esp_err_t tcpip_adapter_set_ip_info(tcpip_adapter_if_t tcpip_if, tcpip_adapter_ip_info_t *ip_info);
/**
* @brief create interface's linklocal IPv6 information
*
* @note this function will create a linklocal IPv6 address about input interface,
* if this address status changed to preferred, will call event call back ,
* notify user linklocal IPv6 address has been verified
*
* @param[in] tcpip_if: the interface which we want to set IP information
*
*
* @return ESP_OK
* ESP_ERR_TCPIP_ADAPTER_INVALID_PARAMS
*/
esp_err_t tcpip_adapter_create_ip6_linklocal(tcpip_adapter_if_t tcpip_if);
/**
* @brief get interface's linkloacl IPv6 information
*
* There has an IPv6 information copy in adapter library, if interface is up,and IPv6 info
* is preferred,it will get IPv6 linklocal IP successfully
*
* @param[in] tcpip_if: the interface which we want to set IP information
* @param[in] if_ip6: If successful, IPv6 information will be returned in this argument.
*
* @return ESP_OK
* ESP_ERR_TCPIP_ADAPTER_INVALID_PARAMS
*/
esp_err_t tcpip_adapter_get_ip6_linklocal(tcpip_adapter_if_t tcpip_if, ip6_addr_t *if_ip6);
#if 0
esp_err_t tcpip_adapter_get_mac(tcpip_adapter_if_t tcpip_if, uint8_t *mac);
......
......@@ -119,6 +119,7 @@ typedef __uint64_t uint64_t;
#endif /* _BYTE_ORDER == _LITTLE_ENDIAN */
/* Alignment-agnostic encode/decode bytestream to/from little/big endian. */
#define INLINE __inline__
static INLINE uint16_t
be16dec(const void *pp)
......
......@@ -34,8 +34,8 @@ MEMORY
Enabling Bluetooth & Trace Memory features in menuconfig will decrease
the amount of RAM available.
*/
dram0_0_seg (RW) : org = 0x3FFB0000 + 0x0,
len = 0x50000 - 0x0 - 0x0
dram0_0_seg (RW) : org = 0x3FFB0000 + 0x10000,
len = 0x50000 - 0x0 - 0x10000
/* Flash mapped constant data */
drom0_0_seg (R) : org = 0x3F400010, len = 0x800000
/* RTC fast memory (executable). Persists over deep sleep.
......
无法预览此类型文件
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册