feat(esp32): Add support for esp32
This commit is contained in:
parent
1e056aa445
commit
6650ac7f6e
|
@ -14,24 +14,33 @@ on:
|
|||
jobs:
|
||||
build:
|
||||
runs-on: ubuntu-18.04
|
||||
continue-on-error: true
|
||||
strategy:
|
||||
matrix:
|
||||
target-hardware: [esp8266, esp32]
|
||||
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
with:
|
||||
submodules: recursive
|
||||
|
||||
- name: before_install
|
||||
if: matrix.target-hardware == 'esp8266'
|
||||
run: |
|
||||
sudo apt update
|
||||
sudo apt install -y gcc git wget make libncurses-dev flex bison python python-setuptools python-serial ninja-build
|
||||
wget https://dl.espressif.com/dl/xtensa-lx106-elf-linux64-1.22.0-100-ge567ec7-5.2.0.tar.gz
|
||||
|
||||
- name: install
|
||||
if: matrix.target-hardware == 'esp8266'
|
||||
run: |
|
||||
tar -xzf ./xtensa-lx106-elf-linux64-1.22.0-100-ge567ec7-5.2.0.tar.gz
|
||||
python -m pip install --user -r ./ESP8266_RTOS_SDK/requirements.txt
|
||||
|
||||
- name: script
|
||||
id: script
|
||||
if: matrix.target-hardware == 'esp8266'
|
||||
run: |
|
||||
export IDF_PATH=$PWD/ESP8266_RTOS_SDK
|
||||
export PATH="$PATH:$PWD/xtensa-lx106-elf/bin"
|
||||
|
@ -47,23 +56,32 @@ jobs:
|
|||
# echo "::set-output name=release_tag::UserBuild_$(date +"%Y.%m.%d_%H-%M")"
|
||||
# echo "::set-output name=status::success"
|
||||
|
||||
|
||||
- name: Build for esp32
|
||||
if: matrix.target-hardware == 'esp32'
|
||||
uses: espressif/esp-idf-ci-action@v1
|
||||
with:
|
||||
esp_idf_version: v4.2
|
||||
target: esp32
|
||||
path: './'
|
||||
|
||||
|
||||
- name: Merge bin files
|
||||
id: merge
|
||||
if: steps.script.outputs.status == 'success' && !cancelled()
|
||||
if: matrix.target-hardware != 'esp8266' || matrix.target-hardware == 'esp8266' && steps.script.outputs.status == 'success' && !cancelled()
|
||||
run: |
|
||||
git clone https://github.com/espressif/esptool.git
|
||||
python3 ./esptool/esptool.py --chip esp8266 merge_bin -o build/esp8266_dap_full.bin 0x0 build/bootloader/bootloader.bin 0x8000 build/partition_table/partition-table.bin 0x10000 build/esp8266_dap.bin
|
||||
mv build/esp8266_dap.bin build/esp8266_dap_app.bin
|
||||
sudo python3 ./esptool/esptool.py --chip ${{ matrix.target-hardware }} merge_bin -o build/wireless_esp_dap_full.bin 0x0 build/bootloader/bootloader.bin 0x8000 build/partition_table/partition-table.bin 0x10000 build/wireless_esp_dap.bin
|
||||
sudo mv build/wireless_esp_dap.bin build/wireless_esp_dap_app.bin
|
||||
echo "::set-output name=status::success"
|
||||
|
||||
- name: Upload firmware
|
||||
uses: actions/upload-artifact@v2
|
||||
if: steps.merge.outputs.status == 'success' && !cancelled()
|
||||
if: matrix.target-hardware != 'esp8266' || matrix.target-hardware == 'esp8266' && steps.merge.outputs.status == 'success' && !cancelled()
|
||||
with:
|
||||
name: firmware.zip
|
||||
name: firmware_${{ matrix.target-hardware }}.zip
|
||||
path: |
|
||||
${{ env.FIRMWARE }}/esp8266_dap_full.bin
|
||||
${{ env.FIRMWARE }}/esp8266_dap_app.bin
|
||||
${{ env.FIRMWARE }}/bootloader/bootloader.bin
|
||||
${{ env.FIRMWARE }}/partition_table/partition-table.bin
|
||||
|
||||
build/wireless_esp_dap_full.bin
|
||||
build/wireless_esp_dap_app.bin
|
||||
build/bootloader/bootloader.bin
|
||||
build/partition_table/partition-table.bin
|
||||
|
|
|
@ -5,4 +5,4 @@ add_compile_options (-fdiagnostics-color=always)
|
|||
include_directories(${CMAKE_CURRENT_SOURCE_DIR})
|
||||
|
||||
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
|
||||
project(esp8266_dap)
|
||||
project(wireless_esp_dap)
|
||||
|
|
100
README.md
100
README.md
|
@ -13,7 +13,7 @@ test
|
|||
|
||||
## Introduce
|
||||
|
||||
Wireless debugging with ***only one ESP8266*** !
|
||||
Wireless debugging with ***only one ESP Chip*** !
|
||||
|
||||
Realized by USBIP and CMSIS-DAP protocol stack.
|
||||
|
||||
|
@ -27,19 +27,22 @@ For Keil users, we now also support [elaphureLink](https://github.com/windowsair
|
|||
|
||||
## Feature
|
||||
|
||||
1. Debug Communication Mode & Debug Port
|
||||
- [x] SWD(SW-DP)
|
||||
- [x] JTAG(JTAG-DP)
|
||||
- [x] SWJ-DP
|
||||
1. SoC Compatibility
|
||||
- [x] ESP8266/8285
|
||||
- [x] ESP32
|
||||
|
||||
2. USB Communication Mode
|
||||
2. Debug Communication Mode
|
||||
- [x] SWD
|
||||
- [x] JTAG
|
||||
|
||||
3. USB Communication Mode
|
||||
- [x] USB-HID
|
||||
- [x] WCID & WinUSB (Default)
|
||||
|
||||
3. Debug Trace (Uart)
|
||||
4. Debug Trace (Uart)
|
||||
- [x] Uart TCP Bridge
|
||||
|
||||
4. More..
|
||||
5. More..
|
||||
- [x] SWD protocol based on SPI acceleration
|
||||
- [x] ...
|
||||
|
||||
|
@ -67,6 +70,9 @@ There is built-in ipv4 only mDNS server. You can access the device using `dap.lo
|
|||
### Debugger
|
||||
|
||||
|
||||
<details>
|
||||
<summary>ESP8266</summary>
|
||||
|
||||
| SWD | |
|
||||
|----------------|--------|
|
||||
| SWCLK | GPIO14 |
|
||||
|
@ -99,10 +105,56 @@ There is built-in ipv4 only mDNS server. You can access the device using `dap.lo
|
|||
|
||||
> Rx and Tx is used for uart bridge, not enabled by default.
|
||||
|
||||
</details>
|
||||
|
||||
|
||||
<details>
|
||||
<summary>ESP32</summary>
|
||||
|
||||
| SWD | |
|
||||
|----------------|--------|
|
||||
| SWCLK | GPIO14 |
|
||||
| SWDIO | GPIO13 |
|
||||
| TVCC | 3V3 |
|
||||
| GND | GND |
|
||||
|
||||
|
||||
--------------
|
||||
|
||||
|
||||
| JTAG | |
|
||||
|--------------------|---------|
|
||||
| TCK | GPIO14 |
|
||||
| TMS | GPIO13 |
|
||||
| TDI | GPIO19 |
|
||||
| TDO | GPIO18 |
|
||||
| nTRST \(optional\) | GPIO25 |
|
||||
| nRESET | GPIO26 |
|
||||
| TVCC | 3V3 |
|
||||
| GND | GND |
|
||||
|
||||
--------------
|
||||
|
||||
| Other | |
|
||||
|--------------------|---------------|
|
||||
| LED\_WIFI\_STATUS | GPIO27 |
|
||||
| Tx | GPIO10 |
|
||||
| Rx | GPIO9 |
|
||||
|
||||
|
||||
> Rx and Tx is used for uart bridge, not enabled by default.
|
||||
|
||||
|
||||
</details>
|
||||
|
||||
|
||||
----
|
||||
|
||||
## Hardware Reference
|
||||
|
||||
Only a hardware reference for the ESP8266 is currently available.
|
||||
|
||||
|
||||
Here we provide a simple example for reference:
|
||||
|
||||

|
||||
|
@ -127,6 +179,9 @@ See: [Build with Github Action](https://github.com/windowsair/wireless-esp8266-d
|
|||
|
||||
### General build and Flash
|
||||
|
||||
<details>
|
||||
<summary>ESP8266</summary>
|
||||
|
||||
1. Get ESP8266 RTOS Software Development Kit
|
||||
|
||||
The SDK is already included in the project, please use it for subsequent operations.
|
||||
|
@ -145,6 +200,35 @@ python ./idf.py build
|
|||
python ./idf.py -p /dev/ttyS5 flash
|
||||
```
|
||||
|
||||
</details>
|
||||
|
||||
|
||||
<details>
|
||||
<summary>ESP32</summary>
|
||||
|
||||
1. Get esp-idf
|
||||
|
||||
For now, please use esp-idf v4.2: https://github.com/espressif/esp-idf/releases/tag/v4.2
|
||||
|
||||
2. Build & Flash
|
||||
|
||||
Build with ESP-IDF build system.
|
||||
More information can be found at the following link: [Build System](https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html "Build System")
|
||||
|
||||
The following example shows a possible way to build:
|
||||
|
||||
```bash
|
||||
# Build
|
||||
idf.py build
|
||||
# Flash
|
||||
idf.py -p /dev/ttyS5 flash
|
||||
```
|
||||
|
||||
> The `idf.py` in the project root directory is only applicable to the old ESP8266 target. Don't use it in ESP32.
|
||||
|
||||
</details>
|
||||
|
||||
|
||||
> We also provided sample firmware quick evaluation. See [Releases](https://github.com/windowsair/wireless-esp8266-dap/releases)
|
||||
|
||||
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
set(COMPONENT_ADD_INCLUDEDIRS "config include $ENV{IDF_PATH}/components/esp8266/include/esp8266/ $ENV{IDF_PATH}/components/esp_ringbuf/include/")
|
||||
set(COMPONENT_SRCS "./source/DAP.c ./source/DAP_vendor.c ./source/JTAG_DP.c ./source/SW_DP.c ./source/SWO.c ./source/uart_modify.c ./source/spi_op.c ./source/spi_switch.c ./source/dap_utility.c")
|
||||
set(COMPONENT_ADD_INCLUDEDIRS "config include $ENV{IDF_PATH}/components/esp_ringbuf/include/ $ENV{IDF_PATH}/components/")
|
||||
set(COMPONENT_SRCS "./source/DAP.c ./source/DAP_vendor.c ./source/JTAG_DP.c ./source/SW_DP.c ./source/SWO.c ./source/spi_op.c ./source/spi_switch.c ./source/dap_utility.c")
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -54,9 +54,15 @@
|
|||
#include "components/DAP/include/spi_switch.h"
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#include "gpio.h"
|
||||
#include "gpio_struct.h"
|
||||
#include "esp8266/include/esp8266/gpio_struct.h"
|
||||
#include "esp8266/pin_mux_register.h"
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
#else
|
||||
#error unknown hardware
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
|
@ -83,8 +89,14 @@ This information includes:
|
|||
|
||||
/// Processor Clock of the Cortex-M MCU used in the Debug Unit.
|
||||
/// This value is used to calculate the SWD/JTAG clock speed.
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#define CPU_CLOCK 160000000 ///< Specifies the CPU Clock in Hz.
|
||||
// <<<<<<<<<<<<<<<<<<<<<<<<<<<<<160MHz
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
#define CPU_CLOCK 240000000
|
||||
// <<<<<<<<<<<<<<<<<<<<<<<<<<<<<240MHz
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
//#define MAX_USER_CLOCK 16000000 ///< Specifies the max Debug Clock in Hz.
|
||||
|
@ -210,6 +222,7 @@ __STATIC_INLINE uint8_t DAP_GetSerNumString(char *str)
|
|||
|
||||
// Note: DO NOT modify these pins: PIN_SWDIO PIN_SWDIO_MOSI PIN_SWCLK
|
||||
// Modify the following pins carefully: PIN_TDO
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#define PIN_SWDIO 12 // SPI MISO
|
||||
#define PIN_SWDIO_MOSI 13 // SPI MOSI
|
||||
#define PIN_SWCLK 14
|
||||
|
@ -221,6 +234,20 @@ __STATIC_INLINE uint8_t DAP_GetSerNumString(char *str)
|
|||
#define PIN_LED_CONNECTED 2
|
||||
// LED_BUILTIN
|
||||
#define PIN_LED_RUNNING _ // won't be used
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
#define PIN_SWDIO 12 // SPI MISO
|
||||
#define PIN_SWDIO_MOSI 13 // SPI MOSI
|
||||
#define PIN_SWCLK 14
|
||||
#define PIN_TDO 19 // device TDO -> Host Data Input ~~~(use RTC pin 16)~~~
|
||||
#define PIN_TDI 18
|
||||
#define PIN_nTRST 25 // optional
|
||||
#define PIN_nRESET 26
|
||||
// LED_BUILTIN
|
||||
#define PIN_LED_CONNECTED 27
|
||||
// LED_BUILTIN
|
||||
#define PIN_LED_RUNNING _ // won't be used
|
||||
#endif
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
/**
|
||||
|
@ -264,6 +291,7 @@ of the same I/O port. The following SWDIO I/O Pin functions are provided:
|
|||
* - TDO to ***input*** mode.
|
||||
*
|
||||
*/
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
__STATIC_INLINE void PORT_JTAG_SETUP(void)
|
||||
{
|
||||
gpio_pin_reg_t pin_reg;
|
||||
|
@ -320,6 +348,39 @@ __STATIC_INLINE void PORT_JTAG_SETUP(void)
|
|||
pin_reg.pullup = 1;
|
||||
WRITE_PERI_REG(GPIO_PIN_REG(PIN_nRESET), pin_reg.val);
|
||||
}
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
__STATIC_INLINE void PORT_JTAG_SETUP(void)
|
||||
{
|
||||
// set TCK, TMS pin
|
||||
//// FIXME: esp32
|
||||
//DAP_SPI_Deinit();
|
||||
|
||||
|
||||
// PIN_TDO output disable
|
||||
GPIO.enable_w1tc = (0x1 << PIN_TDO);
|
||||
// PIN_TDO input enable
|
||||
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[PIN_TDO]);
|
||||
|
||||
|
||||
|
||||
// gpio_set_direction(PIN_TDI, GPIO_MODE_OUTPUT);
|
||||
GPIO.enable_w1ts = (0x1 << PIN_TDI);
|
||||
GPIO.pin[PIN_TDI].pad_driver = 0;
|
||||
REG_CLR_BIT(GPIO_PIN_MUX_REG[PIN_TDI], FUN_PD); // disable pull down
|
||||
|
||||
// gpio_set_direction(PIN_nTRST, GPIO_MODE_OUTPUT_OD);
|
||||
// gpio_set_direction(PIN_nRESET, GPIO_MODE_OUTPUT_OD);
|
||||
GPIO.enable_w1tc = (0x1 << PIN_nTRST);
|
||||
GPIO.pin[PIN_nTRST].pad_driver = 1;
|
||||
GPIO.enable_w1tc = (0x1 << PIN_nRESET);
|
||||
GPIO.pin[PIN_nRESET].pad_driver = 1;
|
||||
|
||||
// gpio_set_pull_mode(PIN_nTRST, GPIO_PULLUP_ONLY);
|
||||
// gpio_set_pull_mode(PIN_nRESET, GPIO_PULLUP_ONLY);
|
||||
GPIO_PULL_UP_ONLY_SET(PIN_nTRST);
|
||||
GPIO_PULL_UP_ONLY_SET(PIN_nRESET);
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Setup SWD I/O pins: SWCLK, SWDIO, and nRESET.
|
||||
|
@ -479,7 +540,13 @@ __STATIC_FORCEINLINE void PIN_SWDIO_OUT_DISABLE(void)
|
|||
// esp8266 input is always connected
|
||||
// GPIO.enable_w1tc |= (0x1 << PIN_SWDIO_MOSI);
|
||||
// GPIO.pin[PIN_SWDIO_MOSI].driver = 0;
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
GPIO.out_w1ts |= (0x1 << PIN_SWDIO_MOSI);
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
// Note that the input of esp32 is not always connected.
|
||||
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[PIN_SWDIO_MOSI]);
|
||||
GPIO.out_w1ts = (0x1 << PIN_SWDIO_MOSI);
|
||||
#endif
|
||||
}
|
||||
|
||||
// TDI Pin I/O ---------------------------------------------
|
||||
|
@ -525,7 +592,11 @@ __STATIC_FORCEINLINE void PIN_TDI_OUT(uint32_t bit)
|
|||
*/
|
||||
__STATIC_FORCEINLINE uint32_t PIN_TDO_IN(void)
|
||||
{
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
return READ_PERI_REG(RTC_GPIO_IN_DATA) & 0x1;
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
return ((GPIO.in >> PIN_TDO) & 0x1) ? 1 : 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
// nTRST Pin I/O -------------------------------------------
|
||||
|
|
|
@ -18,6 +18,10 @@
|
|||
#define __UNUSED __attribute__((unused))
|
||||
#endif
|
||||
|
||||
#include "sdkconfig.h"
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#define GPIO_PIN_REG_0 PERIPHS_IO_MUX_GPIO0_U
|
||||
#define GPIO_PIN_REG_1 PERIPHS_IO_MUX_U0TXD_U
|
||||
#define GPIO_PIN_REG_2 PERIPHS_IO_MUX_GPIO2_U
|
||||
|
@ -53,5 +57,7 @@
|
|||
(i==14)? GPIO_PIN_REG_14: \
|
||||
(i==15)? GPIO_PIN_REG_15: \
|
||||
GPIO_PIN_REG_16
|
||||
#endif
|
||||
|
||||
|
||||
#endif
|
|
@ -1,14 +1,36 @@
|
|||
/**
|
||||
* @file gpio_op.h
|
||||
* @author windowsair
|
||||
* @brief esp GPIO operation
|
||||
* @version 0.1
|
||||
* @date 2021-03-03
|
||||
*
|
||||
* @copyright Copyright (c) 2021
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __GPIO_OP_H__
|
||||
#define __GPIO_OP_H__
|
||||
|
||||
#include "sdkconfig.h"
|
||||
#include "components/DAP/include/cmsis_compiler.h"
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#include "gpio.h"
|
||||
#include "gpio_struct.h"
|
||||
#include "timer_struct.h"
|
||||
#include "esp8266/include/esp8266/gpio_struct.h"
|
||||
#include "esp8266/include/esp8266/timer_struct.h"
|
||||
#include "esp8266/pin_mux_register.h"
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
// soc register
|
||||
// #include "soc/soc/esp32/rom/gpio.h"
|
||||
#include "soc/soc/esp32/include/soc/gpio_struct.h"
|
||||
#include "hal/gpio_types.h"
|
||||
#else
|
||||
#error unknown hardware
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
__STATIC_INLINE __UNUSED void GPIO_FUNCTION_SET(int io_num)
|
||||
{
|
||||
gpio_pin_reg_t pin_reg;
|
||||
|
@ -27,14 +49,31 @@ __STATIC_INLINE __UNUSED void GPIO_FUNCTION_SET(int io_num)
|
|||
|
||||
WRITE_PERI_REG(GPIO_PIN_REG(io_num), pin_reg.val);
|
||||
}
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
__STATIC_INLINE void GPIO_FUNCTION_SET(int io_num)
|
||||
{
|
||||
// function number 2 is GPIO_FUNC for each pin
|
||||
// Note that the index starts at 0, so we are using function 3.
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[io_num], PIN_FUNC_GPIO);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
__UNUSED static void GPIO_SET_DIRECTION_NORMAL_OUT(int io_num)
|
||||
{
|
||||
GPIO.enable_w1ts |= (0x1 << io_num);
|
||||
// PP out
|
||||
GPIO.pin[io_num].driver = 0;
|
||||
}
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
static void GPIO_SET_DIRECTION_NORMAL_OUT(int io_num)
|
||||
{
|
||||
GPIO.enable_w1ts = (0x1 << io_num);
|
||||
// PP out
|
||||
GPIO.pin[io_num].pad_driver = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
__STATIC_INLINE __UNUSED void GPIO_SET_LEVEL_HIGH(int io_num)
|
||||
|
@ -43,6 +82,19 @@ __STATIC_INLINE __UNUSED void GPIO_SET_LEVEL_HIGH(int io_num)
|
|||
|
||||
}
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP32
|
||||
__STATIC_INLINE void GPIO_PULL_UP_ONLY_SET(int io_num)
|
||||
{
|
||||
// disable pull down
|
||||
REG_CLR_BIT(GPIO_PIN_MUX_REG[io_num], FUN_PD);
|
||||
// enable pull up
|
||||
REG_SET_BIT(GPIO_PIN_MUX_REG[io_num], FUN_PU);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
//FIXME: esp32
|
||||
__STATIC_INLINE __UNUSED void GPIO_SET_LEVEL_LOW(int io_num)
|
||||
{
|
||||
GPIO.out_w1tc |= (0x1 << io_num);
|
||||
|
|
|
@ -12,6 +12,7 @@ void DAP_SPI_Read_Data(uint32_t* resData, uint8_t* resParity);
|
|||
void DAP_SPI_Write_Data(uint32_t data, uint8_t parity);
|
||||
|
||||
void DAP_SPI_Generate_Cycle(uint8_t num);
|
||||
void DAP_SPI_Fast_Cycle();
|
||||
|
||||
void DAP_SPI_Protocol_Error_Read();
|
||||
void DAP_SPI_Protocol_Error_Write();
|
||||
|
|
|
@ -6,5 +6,7 @@ void DAP_SPI_Deinit();
|
|||
void DAP_SPI_Enable();
|
||||
void DAP_SPI_Disable();
|
||||
|
||||
void DAP_SPI_Acquire();
|
||||
void DAP_SPI_Release();
|
||||
|
||||
#endif
|
||||
|
|
|
@ -412,6 +412,7 @@ static uint32_t DAP_SWJ_Clock(const uint8_t *request, uint8_t *response) {
|
|||
DAP_Data.fast_clock = 0U;
|
||||
SWD_TransferSpeed = kTransfer_GPIO_normal;
|
||||
|
||||
////FIXME: esp32
|
||||
#define CPU_CLOCK_FIXED 80000000
|
||||
|
||||
delay = ((CPU_CLOCK_FIXED/2U) + (clock - 1U)) / clock;
|
||||
|
|
|
@ -101,7 +101,7 @@ void SWD_Sequence_SPI (uint32_t info, const uint8_t *swdo, uint8_t *swdi);
|
|||
void SWJ_Sequence (uint32_t count, const uint8_t *data) {
|
||||
// if (count != 8 && count != 16 && count!= 51)
|
||||
// {
|
||||
// printf("[ERROR] wrong SWJ Swquence length:%d\r\n", (int)count);
|
||||
// os_printf("[ERROR] wrong SWJ Swquence length:%d\r\n", (int)count);
|
||||
// return;
|
||||
// }
|
||||
|
||||
|
@ -242,44 +242,44 @@ static uint8_t SWD_Transfer_SPI (uint32_t request, uint32_t *data) {
|
|||
switch (requestByte)
|
||||
{
|
||||
case 0xA5U:
|
||||
printf("IDCODE\r\n");
|
||||
os_printf("IDCODE\r\n");
|
||||
break;
|
||||
case 0xA9U:
|
||||
printf("W CTRL/STAT\r\n");
|
||||
os_printf("W CTRL/STAT\r\n");
|
||||
break;
|
||||
case 0xBDU:
|
||||
printf("RDBUFF\r\n");
|
||||
os_printf("RDBUFF\r\n");
|
||||
break;
|
||||
case 0x8DU:
|
||||
printf("R CTRL/STAT\r\n");
|
||||
os_printf("R CTRL/STAT\r\n");
|
||||
break;
|
||||
case 0x81U:
|
||||
printf("W ABORT\r\n");
|
||||
os_printf("W ABORT\r\n");
|
||||
break;
|
||||
case 0xB1U:
|
||||
printf("W SELECT\r\n");
|
||||
os_printf("W SELECT\r\n");
|
||||
break;
|
||||
case 0xBBU:
|
||||
printf("W APc\r\n");
|
||||
os_printf("W APc\r\n");
|
||||
break;
|
||||
case 0x9FU:
|
||||
printf("R APc\r\n");
|
||||
os_printf("R APc\r\n");
|
||||
break;
|
||||
case 0x8BU:
|
||||
printf("W AP4\r\n");
|
||||
os_printf("W AP4\r\n");
|
||||
break;
|
||||
case 0xA3U:
|
||||
printf("W AP0\r\n");
|
||||
os_printf("W AP0\r\n");
|
||||
break;
|
||||
case 0X87U:
|
||||
printf("R AP0\r\n");
|
||||
os_printf("R AP0\r\n");
|
||||
break;
|
||||
case 0xB7U:
|
||||
printf("R AP8\r\n");
|
||||
os_printf("R AP8\r\n");
|
||||
break;
|
||||
default:
|
||||
//W AP8
|
||||
printf("Unknown:%08x\r\n", requestByte);
|
||||
os_printf("Unknown:%08x\r\n", requestByte);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
@ -304,9 +304,10 @@ static uint8_t SWD_Transfer_SPI (uint32_t request, uint32_t *data) {
|
|||
|
||||
}
|
||||
else if ((ack == DAP_TRANSFER_WAIT) || (ack == DAP_TRANSFER_FAULT)) {
|
||||
////FIXME: esp32 // DAP_SPI_Fast_Cycle();
|
||||
DAP_SPI_Generate_Cycle(1);
|
||||
#if (PRINT_SWD_PROTOCOL == 1)
|
||||
printf("WAIT\r\n");
|
||||
os_printf("WAIT\r\n");
|
||||
#endif
|
||||
|
||||
// return DAP_TRANSFER_WAIT;
|
||||
|
@ -322,7 +323,7 @@ static uint8_t SWD_Transfer_SPI (uint32_t request, uint32_t *data) {
|
|||
DAP_SPI_Disable();
|
||||
PIN_SWDIO_TMS_SET();
|
||||
#if (PRINT_SWD_PROTOCOL == 1)
|
||||
printf("Protocol Error: Read\r\n");
|
||||
os_printf("Protocol Error: Read\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -352,7 +353,7 @@ static uint8_t SWD_Transfer_SPI (uint32_t request, uint32_t *data) {
|
|||
|
||||
/* TODO: overrun transfer -> for read */
|
||||
#if (PRINT_SWD_PROTOCOL == 1)
|
||||
printf("WAIT\r\n");
|
||||
os_printf("WAIT\r\n");
|
||||
#endif
|
||||
|
||||
}
|
||||
|
@ -368,7 +369,7 @@ static uint8_t SWD_Transfer_SPI (uint32_t request, uint32_t *data) {
|
|||
PIN_SWDIO_TMS_SET();
|
||||
|
||||
#if (PRINT_SWD_PROTOCOL == 1)
|
||||
printf("Protocol Error: Write\r\n");
|
||||
os_printf("Protocol Error: Write\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -11,6 +11,8 @@
|
|||
* @copyright Copyright (c) 2021
|
||||
*
|
||||
*/
|
||||
#include "sdkconfig.h"
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
|
@ -18,11 +20,35 @@
|
|||
|
||||
#include "components/DAP/include/cmsis_compiler.h"
|
||||
#include "components/DAP/include/spi_op.h"
|
||||
#include "components/DAP/include/spi_switch.h"
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#include "esp8266/spi_struct.h"
|
||||
|
||||
|
||||
#define DAP_SPI SPI1
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
#include "soc/soc/esp32/include/soc/gpio_struct.h"
|
||||
#include "hal/gpio_types.h"
|
||||
|
||||
#include "soc/soc/esp32/include/soc/dport_access.h"
|
||||
#include "soc/soc/esp32/include/soc/dport_reg.h"
|
||||
#include "soc/soc/esp32/include/soc/periph_defs.h"
|
||||
#include "soc/soc/esp32/include/soc/spi_struct.h"
|
||||
#include "soc/soc/esp32/include/soc/spi_reg.h"
|
||||
|
||||
#define DAP_SPI SPI2
|
||||
#else
|
||||
#error unknown hardware
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#define SET_MOSI_BIT_LEN(x) DAP_SPI.user1.usr_mosi_bitlen = x
|
||||
#define SET_MISO_BIT_LEN(x) DAP_SPI.user1.usr_miso_bitlen = x
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
#define SET_MOSI_BIT_LEN(x) DAP_SPI.mosi_dlen.usr_mosi_dbitlen = x
|
||||
#define SET_MISO_BIT_LEN(x) DAP_SPI.miso_dlen.usr_miso_dbitlen = x
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Calculate integer division and round up
|
||||
|
@ -50,7 +76,7 @@ void DAP_SPI_WriteBits(const uint8_t count, const uint8_t *buf)
|
|||
|
||||
// have data to send
|
||||
DAP_SPI.user.usr_mosi = 1;
|
||||
DAP_SPI.user1.usr_mosi_bitlen = count - 1;
|
||||
SET_MOSI_BIT_LEN(count - 1);
|
||||
// copy data to reg
|
||||
switch (count)
|
||||
{
|
||||
|
@ -113,7 +139,7 @@ void DAP_SPI_ReadBits(const uint8_t count, uint8_t *buf) {
|
|||
DAP_SPI.user.sio = true;
|
||||
#endif
|
||||
|
||||
DAP_SPI.user1.usr_miso_bitlen = count - 1U;
|
||||
SET_MISO_BIT_LEN(count - 1U);
|
||||
|
||||
// Start transmission
|
||||
DAP_SPI.cmd.usr = 1;
|
||||
|
@ -149,7 +175,7 @@ __FORCEINLINE void DAP_SPI_Send_Header(const uint8_t packetHeaderData, uint8_t *
|
|||
|
||||
// have data to send
|
||||
DAP_SPI.user.usr_mosi = 1;
|
||||
DAP_SPI.user1.usr_mosi_bitlen = 8 - 1;
|
||||
SET_MOSI_BIT_LEN(8 - 1);
|
||||
|
||||
DAP_SPI.user.usr_miso = 1;
|
||||
|
||||
|
@ -158,7 +184,7 @@ __FORCEINLINE void DAP_SPI_Send_Header(const uint8_t packetHeaderData, uint8_t *
|
|||
#endif
|
||||
|
||||
// 1 bit Trn(Before ACK) + 3bits ACK + TrnAferACK - 1(prescribed)
|
||||
DAP_SPI.user1.usr_miso_bitlen = 1U + 3U + TrnAfterACK - 1U;
|
||||
SET_MISO_BIT_LEN(1U + 3U + TrnAfterACK - 1U);
|
||||
|
||||
// copy data to reg
|
||||
DAP_SPI.data_buf[0] = (packetHeaderData << 0) | (0U << 8) | (0U << 16) | (0U << 24);
|
||||
|
@ -196,7 +222,7 @@ __FORCEINLINE void DAP_SPI_Read_Data(uint32_t *resData, uint8_t *resParity)
|
|||
#endif
|
||||
|
||||
// 1 bit Trn(End) + 3bits ACK + 32bis data + 1bit parity - 1(prescribed)
|
||||
DAP_SPI.user1.usr_miso_bitlen = 1U + 32U + 1U - 1U;
|
||||
SET_MISO_BIT_LEN(1U + 32U + 1U - 1U);
|
||||
|
||||
// Start transmission
|
||||
DAP_SPI.cmd.usr = 1;
|
||||
|
@ -225,7 +251,7 @@ __FORCEINLINE void DAP_SPI_Write_Data(uint32_t data, uint8_t parity)
|
|||
DAP_SPI.user.usr_mosi = 1;
|
||||
DAP_SPI.user.usr_miso = 0;
|
||||
|
||||
DAP_SPI.user1.usr_mosi_bitlen = 32U + 1U - 1U; // 32bis data + 1bit parity - 1(prescribed)
|
||||
SET_MOSI_BIT_LEN(32U + 1U - 1U);
|
||||
|
||||
// copy data to reg
|
||||
DAP_SPI.data_buf[0] = data;
|
||||
|
@ -247,7 +273,7 @@ __FORCEINLINE void DAP_SPI_Generate_Cycle(uint8_t num)
|
|||
//// TODO: It may take long time to generate just one clock
|
||||
DAP_SPI.user.usr_mosi = 1;
|
||||
DAP_SPI.user.usr_miso = 0;
|
||||
DAP_SPI.user1.usr_mosi_bitlen = num - 1U;
|
||||
SET_MOSI_BIT_LEN(num - 1U);
|
||||
|
||||
DAP_SPI.data_buf[0] = 0x00000000U;
|
||||
|
||||
|
@ -255,8 +281,20 @@ __FORCEINLINE void DAP_SPI_Generate_Cycle(uint8_t num)
|
|||
DAP_SPI.cmd.usr = 1;
|
||||
// Wait for sending to complete
|
||||
while (DAP_SPI.cmd.usr) continue;
|
||||
// TODO: not wait?
|
||||
}
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP32
|
||||
/**
|
||||
* @brief Quickly generate 1 clock
|
||||
*
|
||||
*/
|
||||
__FORCEINLINE void DAP_SPI_Fast_Cycle()
|
||||
{
|
||||
DAP_SPI_Release();
|
||||
DAP_SPI_Acquire();
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Generate Protocol Error Cycle
|
||||
|
@ -266,7 +304,7 @@ __FORCEINLINE void DAP_SPI_Protocol_Error_Read()
|
|||
{
|
||||
DAP_SPI.user.usr_mosi = 1;
|
||||
DAP_SPI.user.usr_miso = 0;
|
||||
DAP_SPI.user1.usr_mosi_bitlen = 32U + 1U - 1; // 32bit ignore data + 1 bit - 1(prescribed)
|
||||
SET_MOSI_BIT_LEN(32U + 1U - 1); // 32bit ignore data + 1 bit - 1(prescribed)
|
||||
|
||||
DAP_SPI.data_buf[0] = 0xFFFFFFFFU;
|
||||
DAP_SPI.data_buf[1] = 0xFFFFFFFFU;
|
||||
|
@ -286,7 +324,7 @@ __FORCEINLINE void DAP_SPI_Protocol_Error_Write()
|
|||
{
|
||||
DAP_SPI.user.usr_mosi = 1;
|
||||
DAP_SPI.user.usr_miso = 0;
|
||||
DAP_SPI.user1.usr_mosi_bitlen = 1U + 32U + 1U - 1; // 1bit Trn + 32bit ignore data + 1 bit - 1(prescribed)
|
||||
SET_MOSI_BIT_LEN(1U + 32U + 1U - 1); // 1bit Trn + 32bit ignore data + 1 bit - 1(prescribed)
|
||||
|
||||
DAP_SPI.data_buf[0] = 0xFFFFFFFFU;
|
||||
DAP_SPI.data_buf[1] = 0xFFFFFFFFU;
|
||||
|
|
|
@ -10,18 +10,45 @@
|
|||
* @copyright Copyright (c) 2021
|
||||
*
|
||||
*/
|
||||
#include "sdkconfig.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "components/DAP/include/cmsis_compiler.h"
|
||||
#include "components/DAP/include/spi_switch.h"
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#include "esp8266/spi_struct.h"
|
||||
#include "esp8266/pin_mux_register.h"
|
||||
#include "esp8266/gpio_struct.h"
|
||||
|
||||
|
||||
#define DAP_SPI SPI1
|
||||
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
// soc register
|
||||
#include "soc/soc/esp32/include/soc/gpio_struct.h"
|
||||
#include "hal/gpio_types.h"
|
||||
|
||||
#include "soc/soc/esp32/include/soc/dport_access.h"
|
||||
#include "soc/soc/esp32/include/soc/dport_reg.h"
|
||||
#include "soc/soc/esp32/include/soc/periph_defs.h"
|
||||
#include "soc/soc/esp32/include/soc/spi_struct.h"
|
||||
#include "soc/soc/esp32/include/soc/spi_reg.h"
|
||||
|
||||
#define DAP_SPI SPI2
|
||||
|
||||
// Note that the index starts at 0, so we are using function 2(SPI).
|
||||
#define FUNC_SPI 1
|
||||
|
||||
#define SPI2_HOST 1
|
||||
|
||||
#define SPI_LL_RST_MASK (SPI_OUT_RST | SPI_IN_RST | SPI_AHBM_RST | SPI_AHBM_FIFO_RST)
|
||||
|
||||
#else
|
||||
#error unknown hardware
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
#define ENTER_CRITICAL() portENTER_CRITICAL()
|
||||
#define EXIT_CRITICAL() portEXIT_CRITICAL()
|
||||
|
||||
|
@ -31,6 +58,8 @@ typedef enum {
|
|||
} spi_clk_div_t;
|
||||
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
/**
|
||||
* @brief Initialize on first use
|
||||
*
|
||||
|
@ -134,7 +163,116 @@ void DAP_SPI_Init()
|
|||
DAP_SPI.user.usr_command = 0;
|
||||
DAP_SPI.user.usr_addr = 0;
|
||||
}
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
void DAP_SPI_Init()
|
||||
{
|
||||
// In esp32, the driving of GPIO should be stopped,
|
||||
// otherwise there will be issue in the spi
|
||||
GPIO.out_w1tc = (0x1 << 13);
|
||||
GPIO.out_w1tc = (0x1 << 14);
|
||||
|
||||
// Enable spi module, We use SPI2(HSPI)
|
||||
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_SPI2_CLK_EN);
|
||||
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_SPI2_RST);
|
||||
|
||||
|
||||
// We will use IO_MUX to get the maximum speed.
|
||||
GPIO.func_in_sel_cfg[HSPID_IN_IDX].sig_in_sel = 0; // IO_MUX direct connnect
|
||||
PIN_INPUT_ENABLE(IO_MUX_GPIO13_REG); // MOSI
|
||||
GPIO.func_out_sel_cfg[13].oen_sel = 0; // use output enable signal from peripheral
|
||||
GPIO.func_out_sel_cfg[13].oen_inv_sel = 0; // do not invert the output value
|
||||
PIN_FUNC_SELECT(IO_MUX_GPIO13_REG, FUNC_SPI);
|
||||
|
||||
// GPIO.func_in_sel_cfg[HSPIQ_IN_IDX].sig_in_sel = 0;
|
||||
// PIN_INPUT_ENABLE(IO_MUX_GPIO12_REG); // MISO
|
||||
// GPIO.func_out_sel_cfg[12].oen_sel = 0;
|
||||
// GPIO.func_out_sel_cfg[12].oen_inv_sel = 0;
|
||||
// PIN_FUNC_SELECT(IO_MUX_GPIO12_REG, FUNC_SPI);
|
||||
|
||||
GPIO.func_in_sel_cfg[HSPICLK_IN_IDX].sig_in_sel = 0;
|
||||
PIN_INPUT_ENABLE(IO_MUX_GPIO14_REG); // SCLK
|
||||
GPIO.func_out_sel_cfg[14].oen_sel = 0;
|
||||
GPIO.func_out_sel_cfg[14].oen_inv_sel = 0;
|
||||
PIN_FUNC_SELECT(IO_MUX_GPIO14_REG, FUNC_SPI);
|
||||
|
||||
|
||||
// Not using DMA
|
||||
// esp32 only
|
||||
DPORT_SET_PERI_REG_BITS(DPORT_SPI_DMA_CHAN_SEL_REG, 3, 0, (SPI2_HOST * 2));
|
||||
|
||||
|
||||
// Reset DMA
|
||||
DAP_SPI.dma_conf.val |= SPI_LL_RST_MASK;
|
||||
DAP_SPI.dma_out_link.start = 0;
|
||||
DAP_SPI.dma_in_link.start = 0;
|
||||
DAP_SPI.dma_conf.val &= ~SPI_LL_RST_MASK;
|
||||
// Disable DMA
|
||||
DAP_SPI.dma_conf.dma_continue = 0;
|
||||
|
||||
|
||||
// Set to Master mode
|
||||
DAP_SPI.slave.slave_mode = false;
|
||||
|
||||
|
||||
// use all 64 bytes of the buffer
|
||||
DAP_SPI.user.usr_mosi_highpart = false;
|
||||
DAP_SPI.user.usr_miso_highpart = false;
|
||||
|
||||
|
||||
// Disable cs pin
|
||||
DAP_SPI.user.cs_setup = false;
|
||||
DAP_SPI.user.cs_hold = false;
|
||||
|
||||
// Disable CS signal
|
||||
DAP_SPI.pin.cs0_dis = 1;
|
||||
DAP_SPI.pin.cs1_dis = 1;
|
||||
DAP_SPI.pin.cs2_dis = 1;
|
||||
|
||||
// Duplex transmit
|
||||
DAP_SPI.user.doutdin = false; // half dulex
|
||||
|
||||
|
||||
// Set data bit order
|
||||
DAP_SPI.ctrl.wr_bit_order = 1; // SWD -> LSB
|
||||
DAP_SPI.ctrl.rd_bit_order = 1; // SWD -> LSB
|
||||
// Set data byte order
|
||||
DAP_SPI.user.wr_byte_order = 0; // SWD -> litte_endian && Risc V -> litte_endian
|
||||
DAP_SPI.user.rd_byte_order = 0; // SWD -> litte_endian && Risc V -> litte_endian
|
||||
|
||||
// Set dummy
|
||||
DAP_SPI.user.usr_dummy = 0; // not use
|
||||
|
||||
// Set spi clk: 40Mhz 50% duty
|
||||
// CLEAR_PERI_REG_MASK(PERIPHS_IO_MUX_CONF_U, SPI1_CLK_EQU_SYS_CLK);
|
||||
|
||||
// See esp32 TRM `SPI_CLOCK_REG`
|
||||
DAP_SPI.clock.clk_equ_sysclk = false;
|
||||
DAP_SPI.clock.clkdiv_pre = 0;
|
||||
DAP_SPI.clock.clkcnt_n = SPI_40MHz_DIV - 1;
|
||||
DAP_SPI.clock.clkcnt_h = SPI_40MHz_DIV / 2 - 1;
|
||||
DAP_SPI.clock.clkcnt_l = SPI_40MHz_DIV - 1;
|
||||
// Dummy is not required, but it may still need to be delayed
|
||||
// by half a clock cycle (espressif)
|
||||
|
||||
|
||||
// MISO delay setting
|
||||
DAP_SPI.user.ck_i_edge = true; //// TODO: may be used in slave mode?
|
||||
DAP_SPI.ctrl2.miso_delay_mode = 0;
|
||||
DAP_SPI.ctrl2.miso_delay_num = 0;
|
||||
|
||||
|
||||
// Set the clock polarity and phase CPOL = CPHA = 1
|
||||
DAP_SPI.pin.ck_idle_edge = 1; // HIGH while idle
|
||||
DAP_SPI.user.ck_out_edge = 0;
|
||||
|
||||
// No command and addr for now
|
||||
DAP_SPI.user.usr_command = 0;
|
||||
DAP_SPI.user.usr_addr = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
/**
|
||||
* @brief Switch to GPIO
|
||||
* Note: You may be able to pull the pin high in SPI mode, though you cannot set it to LOW
|
||||
|
@ -160,8 +298,53 @@ __FORCEINLINE void DAP_SPI_Deinit()
|
|||
pin_reg.pullup = 0;
|
||||
WRITE_PERI_REG(GPIO_PIN_REG(13), pin_reg.val);
|
||||
}
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
__FORCEINLINE void DAP_SPI_Deinit()
|
||||
{
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[14], PIN_FUNC_GPIO);
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[13], PIN_FUNC_GPIO); // MOSI
|
||||
//PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[12], PIN_FUNC_GPIO); // MISO
|
||||
|
||||
// enable SWCLK output
|
||||
GPIO.enable_w1ts = (0x01 << 14);
|
||||
|
||||
// disable MISO output connect
|
||||
// GPIO.enable_w1tc = (0x1 << 12);
|
||||
|
||||
// enable MOSI output & input
|
||||
GPIO.enable_w1ts |= (0x1 << 13);
|
||||
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[13]);
|
||||
|
||||
// enable MOSI OD output
|
||||
//GPIO.pin[13].pad_driver = 1;
|
||||
|
||||
// disable MOSI pull up
|
||||
// REG_CLR_BIT(GPIO_PIN_MUX_REG[13], FUN_PU);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP32
|
||||
/**
|
||||
* @brief Gain control of SPI
|
||||
*
|
||||
*/
|
||||
__FORCEINLINE void DAP_SPI_Acquire()
|
||||
{
|
||||
PIN_FUNC_SELECT(IO_MUX_GPIO14_REG, FUNC_SPI);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Release control of SPI
|
||||
*
|
||||
*/
|
||||
__FORCEINLINE void DAP_SPI_Release()
|
||||
{
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[14], PIN_FUNC_GPIO);
|
||||
GPIO.enable_w1ts = (0x01 << 14);
|
||||
}
|
||||
#endif // CONFIG_IDF_TARGET_ESP32
|
||||
/**
|
||||
* @brief Use SPI acclerate
|
||||
*
|
||||
|
@ -169,7 +352,9 @@ __FORCEINLINE void DAP_SPI_Deinit()
|
|||
void DAP_SPI_Enable()
|
||||
{
|
||||
// may be unuse
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTCK_U, FUNC_HSPID_MOSI); // GPIO13 is SPI MOSI pin (Master Data Out)
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -11,6 +11,7 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "main/usbip_server.h"
|
||||
#include "main/wifi_configuration.h"
|
||||
|
||||
#include "components/USBIP/usb_handle.h"
|
||||
#include "components/USBIP/usb_descriptor.h"
|
||||
|
@ -25,7 +26,7 @@
|
|||
const char *strings_list[] = {
|
||||
0, // reserved: available languages -> iInterface
|
||||
"windowsair",
|
||||
"esp8266 CMSIS-DAP",
|
||||
"Wireless ESP CMSIS-DAP",
|
||||
"1234",
|
||||
};
|
||||
// handle functions
|
||||
|
|
|
@ -153,7 +153,7 @@ void handle_swo_trace_response(usbip_stage2_header *header)
|
|||
if (kSwoTransferBusy)
|
||||
{
|
||||
// busy indicates that there is data to be send
|
||||
printf("swo use data\r\n");
|
||||
os_printf("swo use data\r\n");
|
||||
send_stage2_submit_data(header, 0, (void *)swo_data_to_send, swo_data_num);
|
||||
SWO_TransferComplete();
|
||||
}
|
||||
|
|
|
@ -62,7 +62,7 @@ static int udp_output(const char *buf, int len, ikcpcb *kcp, void *user)
|
|||
// os_printf("fail to send, retry\r\n");
|
||||
int errcode = errno;
|
||||
if (errno != ENOMEM)
|
||||
printf("unknown errcode %d\r\n", errcode);
|
||||
os_printf("unknown errcode %d\r\n", errcode);
|
||||
vTaskDelay(pdMS_TO_TICKS(time));
|
||||
time += 10;
|
||||
}
|
||||
|
|
|
@ -8,10 +8,10 @@
|
|||
void esp_print_tasks(void)
|
||||
{
|
||||
char *pbuffer = (char *)calloc(1, 2048);
|
||||
printf("--------------- heap:%u ---------------------\r\n", esp_get_free_heap_size());
|
||||
os_printf("--------------- heap:%u ---------------------\r\n", esp_get_free_heap_size());
|
||||
vTaskGetRunTimeStats(pbuffer);
|
||||
printf("%s", pbuffer);
|
||||
printf("----------------------------------------------\r\n");
|
||||
os_printf("%s", pbuffer);
|
||||
os_printf("----------------------------------------------\r\n");
|
||||
free(pbuffer);
|
||||
}
|
||||
|
||||
|
|
|
@ -43,7 +43,7 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
|||
#define EVENTS_QUEUE_SIZE 50
|
||||
|
||||
#ifdef CALLBACK_DEBUG
|
||||
#define debug(s, ...) printf("%s: " s "\n", "Cb:", ##__VA_ARGS__)
|
||||
#define debug(s, ...) os_printf("%s: " s "\n", "Cb:", ##__VA_ARGS__)
|
||||
#else
|
||||
#define debug(s, ...)
|
||||
#endif
|
||||
|
@ -105,13 +105,13 @@ static void set_tcp_server_netconn(struct netconn **nc, uint16_t port, netconn_c
|
|||
{
|
||||
if (nc == NULL)
|
||||
{
|
||||
printf("%s: netconn missing .\n", __FUNCTION__);
|
||||
os_printf("%s: netconn missing .\n", __FUNCTION__);
|
||||
return;
|
||||
}
|
||||
*nc = netconn_new_with_callback(NETCONN_TCP, netCallback);
|
||||
if (!*nc)
|
||||
{
|
||||
printf("Status monitor: Failed to allocate netconn.\n");
|
||||
os_printf("Status monitor: Failed to allocate netconn.\n");
|
||||
return;
|
||||
}
|
||||
netconn_set_nonblocking(*nc, NETCONN_FLAG_NON_BLOCKING);
|
||||
|
@ -136,7 +136,7 @@ void tcp_netconn_task()
|
|||
struct netconn *nc = NULL; // To create servers
|
||||
|
||||
set_tcp_server_netconn(&nc, PORT, netCallback);
|
||||
printf("Server netconn %u ready on port %u.\n", (uint32_t)nc, PORT);
|
||||
os_printf("Server netconn %u ready on port %u.\n", (uint32_t)nc, PORT);
|
||||
|
||||
struct netbuf *netbuf = NULL; // To store incoming Data
|
||||
struct netconn *nc_in = NULL; // To accept incoming netconn
|
||||
|
@ -151,14 +151,14 @@ void tcp_netconn_task()
|
|||
|
||||
if (events.nc->state == NETCONN_LISTEN) // If netconn is a server and receive incoming event on it
|
||||
{
|
||||
printf("Client incoming on server %u.\n", (uint32_t)events.nc);
|
||||
os_printf("Client incoming on server %u.\n", (uint32_t)events.nc);
|
||||
int err = netconn_accept(events.nc, &nc_in);
|
||||
if (err != ERR_OK)
|
||||
{
|
||||
if (nc_in)
|
||||
netconn_delete(nc_in);
|
||||
}
|
||||
printf("New client is %u.\n", (uint32_t)nc_in);
|
||||
os_printf("New client is %u.\n", (uint32_t)nc_in);
|
||||
ip_addr_t client_addr; // Address port
|
||||
uint16_t client_port; // Client port
|
||||
netconn_peer(nc_in, &client_addr, &client_port);
|
||||
|
@ -187,7 +187,7 @@ void tcp_netconn_task()
|
|||
emulate((uint8_t *)buffer, len_buf);
|
||||
break;
|
||||
default:
|
||||
printf("unkonw kstate!\r\n");
|
||||
os_printf("unkonw kstate!\r\n");
|
||||
}
|
||||
} while (netbuf_next(netbuf) >= 0);
|
||||
netbuf_delete(netbuf);
|
||||
|
|
16
main/timer.c
16
main/timer.c
|
@ -14,7 +14,10 @@
|
|||
|
||||
#include "main/timer.h"
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#include "hw_timer.h"
|
||||
#endif
|
||||
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/event_groups.h"
|
||||
|
@ -26,12 +29,14 @@
|
|||
bus frequency, so they will not be affected by CPU frequency either.
|
||||
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#define TIMER_BASE 0x60000600
|
||||
volatile frc2_struct_t * frc2 = (frc2_struct_t *)(TIMER_BASE + (1) * 0x20);
|
||||
#endif
|
||||
|
||||
void timer_init()
|
||||
{
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
vPortEnterCritical();
|
||||
frc2->ctrl.div = TIMER_CLKDIV_16; // 80MHz / 16 = 5MHz
|
||||
frc2->ctrl.intr_type = TIMER_EDGE_INT;
|
||||
|
@ -39,11 +44,20 @@ void timer_init()
|
|||
frc2->load.val = 0x7FFFFFFF; // 31bit max
|
||||
frc2->ctrl.en = 0x01;
|
||||
vPortExitCritical();
|
||||
#endif
|
||||
}
|
||||
|
||||
// Timing up to 2147483647(0x7FFFFFFF) / 5000000(5MHz) = 429s
|
||||
// 0.2 micro-second resolution
|
||||
uint32_t get_timer_count()
|
||||
{
|
||||
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
return (uint32_t)frc2->count.data;
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
return 0;
|
||||
#else
|
||||
#error unknown hardware
|
||||
#endif
|
||||
}
|
|
@ -25,7 +25,9 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "sdkconfig.h"
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
// FRC2 is a 32-bit countup timer
|
||||
typedef struct {
|
||||
union {
|
||||
|
@ -64,6 +66,7 @@ typedef struct {
|
|||
} frc2_struct_t;
|
||||
|
||||
extern volatile frc2_struct_t* frc2;
|
||||
#endif
|
||||
|
||||
extern void timer_init();
|
||||
extern uint32_t get_timer_count();
|
||||
|
|
|
@ -23,6 +23,8 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
|||
* @copyright Copyright (c) 2021
|
||||
*
|
||||
*/
|
||||
#include "sdkconfig.h"
|
||||
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/param.h>
|
||||
|
@ -51,11 +53,21 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
|||
|
||||
#if (USE_UART_BRIDGE == 1)
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#define UART_BRIDGE_TX UART_NUM_0
|
||||
#define UART_BRIDGE_RX UART_NUM_1
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
#define UART_BRIDGE_TX UART_NUM_2
|
||||
#define UART_BRIDGE_RX UART_NUM_2
|
||||
#else
|
||||
#error unknown hardware
|
||||
#endif
|
||||
|
||||
#define EVENTS_QUEUE_SIZE 10
|
||||
#define UART_BUF_SIZE 512
|
||||
|
||||
#ifdef CALLBACK_DEBUG
|
||||
#define debug(s, ...) printf("%s: " s "\n", "Cb:", ##__VA_ARGS__)
|
||||
#define debug(s, ...) os_printf("%s: " s "\n", "Cb:", ##__VA_ARGS__)
|
||||
#else
|
||||
#define debug(s, ...)
|
||||
#endif
|
||||
|
@ -168,11 +180,18 @@ static void uart_bridge_setup() {
|
|||
.parity = UART_PARITY_DISABLE,
|
||||
.stop_bits = UART_STOP_BITS_1,
|
||||
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE};
|
||||
uart_param_config(UART_NUM_0, &uart_config);
|
||||
uart_param_config(UART_NUM_1, &uart_config);
|
||||
|
||||
uart_driver_install(UART_NUM_0, UART_BUF_SIZE, 0, 0, NULL, 0); // RX only
|
||||
uart_driver_install(UART_NUM_1, 0, UART_BUF_SIZE, 0, NULL, 0); // TX only
|
||||
if (UART_BRIDGE_TX == UART_BRIDGE_RX) {
|
||||
uart_param_config(UART_BRIDGE_RX, &uart_config);
|
||||
uart_driver_install(UART_BRIDGE_RX, UART_BUF_SIZE, UART_BUF_SIZE, 0, NULL, 0);
|
||||
} else {
|
||||
uart_param_config(UART_BRIDGE_RX, &uart_config);
|
||||
uart_param_config(UART_BRIDGE_TX, &uart_config);
|
||||
|
||||
uart_driver_install(UART_BRIDGE_RX, UART_BUF_SIZE, 0, 0, NULL, 0); // RX only
|
||||
uart_driver_install(UART_BRIDGE_TX, 0, UART_BUF_SIZE, 0, NULL, 0); // TX only
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void uart_bridge_init() {
|
||||
|
@ -201,9 +220,9 @@ void uart_bridge_task() {
|
|||
if (ret != pdTRUE) {
|
||||
// timeout
|
||||
if (is_conn_valid) {
|
||||
ESP_ERROR_CHECK(uart_get_buffered_data_len(UART_NUM_0, &uart_buf_len));
|
||||
ESP_ERROR_CHECK(uart_get_buffered_data_len(UART_BRIDGE_RX, &uart_buf_len));
|
||||
uart_buf_len = uart_buf_len > UART_BUF_SIZE ? UART_BUF_SIZE : uart_buf_len;
|
||||
uart_buf_len = uart_read_bytes(UART_NUM_0, uart_read_buffer, uart_buf_len, pdMS_TO_TICKS(5));
|
||||
uart_buf_len = uart_read_bytes(UART_BRIDGE_RX, uart_read_buffer, uart_buf_len, pdMS_TO_TICKS(5));
|
||||
// then send data
|
||||
netconn_write(uart_netconn, uart_read_buffer, uart_buf_len, NETCONN_COPY);
|
||||
}
|
||||
|
@ -240,9 +259,9 @@ void uart_bridge_task() {
|
|||
|
||||
uart_netconn = events.nc;
|
||||
// read data from UART
|
||||
ESP_ERROR_CHECK(uart_get_buffered_data_len(UART_NUM_0, &uart_buf_len));
|
||||
ESP_ERROR_CHECK(uart_get_buffered_data_len(UART_BRIDGE_RX, &uart_buf_len));
|
||||
uart_buf_len = uart_buf_len > UART_BUF_SIZE ? UART_BUF_SIZE : uart_buf_len;
|
||||
uart_buf_len = uart_read_bytes(UART_NUM_0, uart_read_buffer, uart_buf_len, pdMS_TO_TICKS(5));
|
||||
uart_buf_len = uart_read_bytes(UART_BRIDGE_RX, uart_read_buffer, uart_buf_len, pdMS_TO_TICKS(5));
|
||||
// then send data
|
||||
netconn_write(events.nc, uart_read_buffer, uart_buf_len, NETCONN_COPY);
|
||||
|
||||
|
@ -260,15 +279,15 @@ void uart_bridge_task() {
|
|||
int baudrate = atoi(tmp_buff);
|
||||
if (baudrate > 0 && baudrate < 2000000 && num_digits(baudrate) == len_buf) {
|
||||
ESP_LOGI(UART_TAG, "change baud:%d", baudrate);
|
||||
uart_set_baudrate(UART_NUM_0, baudrate);
|
||||
uart_set_baudrate(UART_NUM_1, baudrate);
|
||||
uart_set_baudrate(UART_BRIDGE_RX, baudrate);
|
||||
uart_set_baudrate(UART_BRIDGE_TX, baudrate);
|
||||
is_first_time_recv = false;
|
||||
continue;
|
||||
}
|
||||
}
|
||||
is_first_time_recv = false;
|
||||
}
|
||||
uart_write_bytes(UART_NUM_1, (const char *)buffer, len_buf);
|
||||
uart_write_bytes(UART_BRIDGE_TX, (const char *)buffer, len_buf);
|
||||
} while (netbuf_next(netbuf) >= 0);
|
||||
netbuf_delete(netbuf);
|
||||
} else {
|
||||
|
|
|
@ -10,8 +10,6 @@
|
|||
#ifndef __WIFI_CONFIGURATION__
|
||||
#define __WIFI_CONFIGURATION__
|
||||
|
||||
#define WIFI_SSID "DAP"
|
||||
#define WIFI_PASS "12345678"
|
||||
|
||||
static struct {
|
||||
const char *ssid;
|
||||
|
@ -40,7 +38,7 @@ static struct {
|
|||
|
||||
#define USE_OTA 1
|
||||
|
||||
#define USE_UART_BRIDGE 0
|
||||
#define USE_UART_BRIDGE 1
|
||||
#define UART_BRIDGE_PORT 1234
|
||||
#define UART_BRIDGE_BAUDRATE 74880
|
||||
//
|
||||
|
@ -62,4 +60,10 @@ static struct {
|
|||
#warning KCP is a very experimental feature, and it should not be used under any circumstances. Please make sure what you are doing. Related usbip version: https://github.com/windowsair/usbip-win
|
||||
#endif
|
||||
|
||||
|
||||
extern int printf(const char *, ...);
|
||||
inline int os_printf(const char *__restrict __fmt, ...) {
|
||||
return printf(__fmt, __builtin_va_arg_pack());
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,3 +1,5 @@
|
|||
#include "sdkconfig.h"
|
||||
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/param.h>
|
||||
|
@ -15,7 +17,13 @@
|
|||
#include "esp_event_loop.h"
|
||||
#include "esp_log.h"
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
#define PIN_LED_WIFI_STATUS 15
|
||||
#elif defined CONFIG_IDF_TARGET_ESP32
|
||||
#define PIN_LED_WIFI_STATUS 27
|
||||
#else
|
||||
#error unknown hardware
|
||||
#endif
|
||||
|
||||
static EventGroupHandle_t wifi_event_group;
|
||||
static int ssid_index = 0;
|
||||
|
@ -51,10 +59,13 @@ static esp_err_t event_handler(void *ctx, system_event_t *event) {
|
|||
GPIO_SET_LEVEL_LOW(PIN_LED_WIFI_STATUS);
|
||||
|
||||
os_printf("Disconnect reason : %d\r\n", (int)info->disconnected.reason);
|
||||
|
||||
#ifdef CONFIG_IDF_TARGET_ESP8266
|
||||
if (info->disconnected.reason == WIFI_REASON_BASIC_RATE_NOT_SUPPORT) {
|
||||
/*Switch to 802.11 bgn mode */
|
||||
esp_wifi_set_protocol(ESP_IF_WIFI_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N);
|
||||
}
|
||||
#endif
|
||||
ssid_change();
|
||||
esp_wifi_connect();
|
||||
xEventGroupClearBits(wifi_event_group, IPV4_GOTIP_BIT);
|
||||
|
|
|
@ -0,0 +1 @@
|
|||
# This file is currently only used to trigger the build system's configuration import for different hardware targets
|
|
@ -0,0 +1,999 @@
|
|||
#
|
||||
# Automatically generated file. DO NOT EDIT.
|
||||
# Espressif IoT Development Framework (ESP-IDF) Project Configuration
|
||||
#
|
||||
CONFIG_IDF_CMAKE=y
|
||||
CONFIG_IDF_TARGET="esp32"
|
||||
CONFIG_IDF_TARGET_ESP32=y
|
||||
CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000
|
||||
|
||||
#
|
||||
# SDK tool configuration
|
||||
#
|
||||
CONFIG_SDK_TOOLPREFIX="xtensa-esp32-elf-"
|
||||
# CONFIG_SDK_TOOLCHAIN_SUPPORTS_TIME_WIDE_64_BITS is not set
|
||||
# end of SDK tool configuration
|
||||
|
||||
#
|
||||
# Build type
|
||||
#
|
||||
CONFIG_APP_BUILD_TYPE_APP_2NDBOOT=y
|
||||
# CONFIG_APP_BUILD_TYPE_ELF_RAM is not set
|
||||
CONFIG_APP_BUILD_GENERATE_BINARIES=y
|
||||
CONFIG_APP_BUILD_BOOTLOADER=y
|
||||
CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y
|
||||
# end of Build type
|
||||
|
||||
#
|
||||
# Application manager
|
||||
#
|
||||
CONFIG_APP_COMPILE_TIME_DATE=y
|
||||
# CONFIG_APP_EXCLUDE_PROJECT_VER_VAR is not set
|
||||
# CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR is not set
|
||||
# CONFIG_APP_PROJECT_VER_FROM_CONFIG is not set
|
||||
CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16
|
||||
# end of Application manager
|
||||
|
||||
#
|
||||
# Bootloader config
|
||||
#
|
||||
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y
|
||||
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set
|
||||
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set
|
||||
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_NONE is not set
|
||||
# CONFIG_BOOTLOADER_LOG_LEVEL_NONE is not set
|
||||
# CONFIG_BOOTLOADER_LOG_LEVEL_ERROR is not set
|
||||
# CONFIG_BOOTLOADER_LOG_LEVEL_WARN is not set
|
||||
CONFIG_BOOTLOADER_LOG_LEVEL_INFO=y
|
||||
# CONFIG_BOOTLOADER_LOG_LEVEL_DEBUG is not set
|
||||
# CONFIG_BOOTLOADER_LOG_LEVEL_VERBOSE is not set
|
||||
CONFIG_BOOTLOADER_LOG_LEVEL=3
|
||||
# CONFIG_BOOTLOADER_SPI_CUSTOM_WP_PIN is not set
|
||||
CONFIG_BOOTLOADER_SPI_WP_PIN=7
|
||||
CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y
|
||||
# CONFIG_BOOTLOADER_FACTORY_RESET is not set
|
||||
# CONFIG_BOOTLOADER_APP_TEST is not set
|
||||
CONFIG_BOOTLOADER_WDT_ENABLE=y
|
||||
# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set
|
||||
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
||||
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
||||
# CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP is not set
|
||||
CONFIG_BOOTLOADER_RESERVE_RTC_SIZE=0
|
||||
# CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set
|
||||
# end of Bootloader config
|
||||
|
||||
#
|
||||
# Security features
|
||||
#
|
||||
# CONFIG_SECURE_SIGNED_APPS_NO_SECURE_BOOT is not set
|
||||
# CONFIG_SECURE_BOOT is not set
|
||||
# CONFIG_SECURE_FLASH_ENC_ENABLED is not set
|
||||
# end of Security features
|
||||
|
||||
#
|
||||
# Serial flasher config
|
||||
#
|
||||
CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200
|
||||
CONFIG_ESPTOOLPY_WITH_STUB=y
|
||||
CONFIG_ESPTOOLPY_FLASHMODE_QIO=y
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_DIO is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_DOUT is not set
|
||||
CONFIG_ESPTOOLPY_FLASHMODE="dio"
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ_80M=y
|
||||
# CONFIG_ESPTOOLPY_FLASHFREQ_40M is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHFREQ_26M is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHFREQ_20M is not set
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ="80m"
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_1MB is not set
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_2MB=y
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_4MB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_8MB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHSIZE_16MB is not set
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE="2MB"
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_DETECT=y
|
||||
CONFIG_ESPTOOLPY_BEFORE_RESET=y
|
||||
# CONFIG_ESPTOOLPY_BEFORE_NORESET is not set
|
||||
CONFIG_ESPTOOLPY_BEFORE="default_reset"
|
||||
CONFIG_ESPTOOLPY_AFTER_RESET=y
|
||||
# CONFIG_ESPTOOLPY_AFTER_NORESET is not set
|
||||
CONFIG_ESPTOOLPY_AFTER="hard_reset"
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_9600B is not set
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_57600B is not set
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_115200B is not set
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_230400B is not set
|
||||
CONFIG_ESPTOOLPY_MONITOR_BAUD_921600B=y
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_2MB is not set
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER is not set
|
||||
CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER_VAL=115200
|
||||
CONFIG_ESPTOOLPY_MONITOR_BAUD=921600
|
||||
# end of Serial flasher config
|
||||
|
||||
#
|
||||
# Partition Table
|
||||
#
|
||||
CONFIG_PARTITION_TABLE_SINGLE_APP=y
|
||||
# CONFIG_PARTITION_TABLE_TWO_OTA is not set
|
||||
# CONFIG_PARTITION_TABLE_CUSTOM is not set
|
||||
CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions.csv"
|
||||
CONFIG_PARTITION_TABLE_FILENAME="partitions_singleapp.csv"
|
||||
CONFIG_PARTITION_TABLE_OFFSET=0x8000
|
||||
CONFIG_PARTITION_TABLE_MD5=y
|
||||
# end of Partition Table
|
||||
|
||||
#
|
||||
# Compiler options
|
||||
#
|
||||
# CONFIG_COMPILER_OPTIMIZATION_DEFAULT is not set
|
||||
# CONFIG_COMPILER_OPTIMIZATION_SIZE is not set
|
||||
CONFIG_COMPILER_OPTIMIZATION_PERF=y
|
||||
# CONFIG_COMPILER_OPTIMIZATION_NONE is not set
|
||||
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_ENABLE=y
|
||||
# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT is not set
|
||||
# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_DISABLE is not set
|
||||
# CONFIG_COMPILER_CXX_EXCEPTIONS is not set
|
||||
# CONFIG_COMPILER_CXX_RTTI is not set
|
||||
CONFIG_COMPILER_STACK_CHECK_MODE_NONE=y
|
||||
# CONFIG_COMPILER_STACK_CHECK_MODE_NORM is not set
|
||||
# CONFIG_COMPILER_STACK_CHECK_MODE_STRONG is not set
|
||||
# CONFIG_COMPILER_STACK_CHECK_MODE_ALL is not set
|
||||
# CONFIG_COMPILER_WARN_WRITE_STRINGS is not set
|
||||
# CONFIG_COMPILER_DISABLE_GCC8_WARNINGS is not set
|
||||
# end of Compiler options
|
||||
|
||||
#
|
||||
# Component config
|
||||
#
|
||||
|
||||
#
|
||||
# Application Level Tracing
|
||||
#
|
||||
# CONFIG_APPTRACE_DEST_TRAX is not set
|
||||
CONFIG_APPTRACE_DEST_NONE=y
|
||||
CONFIG_APPTRACE_LOCK_ENABLE=y
|
||||
# end of Application Level Tracing
|
||||
|
||||
#
|
||||
# Bluetooth
|
||||
#
|
||||
# CONFIG_BT_ENABLED is not set
|
||||
CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_EFF=0
|
||||
CONFIG_BTDM_CTRL_PCM_ROLE_EFF=0
|
||||
CONFIG_BTDM_CTRL_PCM_POLAR_EFF=0
|
||||
CONFIG_BTDM_CTRL_BLE_MAX_CONN_EFF=0
|
||||
CONFIG_BTDM_CTRL_BR_EDR_MAX_ACL_CONN_EFF=0
|
||||
CONFIG_BTDM_CTRL_BR_EDR_MAX_SYNC_CONN_EFF=0
|
||||
CONFIG_BTDM_CTRL_PINNED_TO_CORE=0
|
||||
CONFIG_BTDM_BLE_SLEEP_CLOCK_ACCURACY_INDEX_EFF=1
|
||||
CONFIG_BT_RESERVE_DRAM=0
|
||||
# end of Bluetooth
|
||||
|
||||
#
|
||||
# CoAP Configuration
|
||||
#
|
||||
CONFIG_COAP_MBEDTLS_PSK=y
|
||||
# CONFIG_COAP_MBEDTLS_PKI is not set
|
||||
# CONFIG_COAP_MBEDTLS_DEBUG is not set
|
||||
CONFIG_COAP_LOG_DEFAULT_LEVEL=0
|
||||
# end of CoAP Configuration
|
||||
|
||||
#
|
||||
# Driver configurations
|
||||
#
|
||||
|
||||
#
|
||||
# ADC configuration
|
||||
#
|
||||
# CONFIG_ADC_FORCE_XPD_FSM is not set
|
||||
CONFIG_ADC_DISABLE_DAC=y
|
||||
# end of ADC configuration
|
||||
|
||||
#
|
||||
# SPI configuration
|
||||
#
|
||||
CONFIG_SPI_MASTER_IN_IRAM=y
|
||||
CONFIG_SPI_MASTER_ISR_IN_IRAM=y
|
||||
# CONFIG_SPI_SLAVE_IN_IRAM is not set
|
||||
CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||
# end of SPI configuration
|
||||
|
||||
#
|
||||
# UART configuration
|
||||
#
|
||||
# CONFIG_UART_ISR_IN_IRAM is not set
|
||||
# end of UART configuration
|
||||
|
||||
#
|
||||
# RTCIO configuration
|
||||
#
|
||||
# CONFIG_RTCIO_SUPPORT_RTC_GPIO_DESC is not set
|
||||
# end of RTCIO configuration
|
||||
# end of Driver configurations
|
||||
|
||||
#
|
||||
# eFuse Bit Manager
|
||||
#
|
||||
# CONFIG_EFUSE_CUSTOM_TABLE is not set
|
||||
# CONFIG_EFUSE_VIRTUAL is not set
|
||||
# CONFIG_EFUSE_CODE_SCHEME_COMPAT_NONE is not set
|
||||
CONFIG_EFUSE_CODE_SCHEME_COMPAT_3_4=y
|
||||
# CONFIG_EFUSE_CODE_SCHEME_COMPAT_REPEAT is not set
|
||||
CONFIG_EFUSE_MAX_BLK_LEN=192
|
||||
# end of eFuse Bit Manager
|
||||
|
||||
#
|
||||
# ESP-TLS
|
||||
#
|
||||
CONFIG_ESP_TLS_USING_MBEDTLS=y
|
||||
# CONFIG_ESP_TLS_USE_SECURE_ELEMENT is not set
|
||||
# CONFIG_ESP_TLS_SERVER is not set
|
||||
# CONFIG_ESP_TLS_PSK_VERIFICATION is not set
|
||||
# end of ESP-TLS
|
||||
|
||||
#
|
||||
# ESP32-specific
|
||||
#
|
||||
CONFIG_ESP32_REV_MIN_0=y
|
||||
# CONFIG_ESP32_REV_MIN_1 is not set
|
||||
# CONFIG_ESP32_REV_MIN_2 is not set
|
||||
# CONFIG_ESP32_REV_MIN_3 is not set
|
||||
CONFIG_ESP32_REV_MIN=0
|
||||
CONFIG_ESP32_DPORT_WORKAROUND=y
|
||||
# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set
|
||||
# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set
|
||||
CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y
|
||||
CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240
|
||||
# CONFIG_ESP32_SPIRAM_SUPPORT is not set
|
||||
# CONFIG_ESP32_TRAX is not set
|
||||
CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0
|
||||
# CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO is not set
|
||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR=y
|
||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4
|
||||
# CONFIG_ESP32_ULP_COPROC_ENABLED is not set
|
||||
CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=0
|
||||
CONFIG_ESP32_DEBUG_OCDAWARE=y
|
||||
CONFIG_ESP32_BROWNOUT_DET=y
|
||||
CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_0=y
|
||||
# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_1 is not set
|
||||
# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_2 is not set
|
||||
# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_3 is not set
|
||||
# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_4 is not set
|
||||
# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_5 is not set
|
||||
# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_6 is not set
|
||||
# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_7 is not set
|
||||
CONFIG_ESP32_BROWNOUT_DET_LVL=0
|
||||
CONFIG_ESP32_REDUCE_PHY_TX_POWER=y
|
||||
CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y
|
||||
# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set
|
||||
# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set
|
||||
# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set
|
||||
CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y
|
||||
# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set
|
||||
# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set
|
||||
# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set
|
||||
CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024
|
||||
CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000
|
||||
CONFIG_ESP32_XTAL_FREQ_40=y
|
||||
# CONFIG_ESP32_XTAL_FREQ_26 is not set
|
||||
# CONFIG_ESP32_XTAL_FREQ_AUTO is not set
|
||||
CONFIG_ESP32_XTAL_FREQ=40
|
||||
# CONFIG_ESP32_DISABLE_BASIC_ROM_CONSOLE is not set
|
||||
# CONFIG_ESP32_NO_BLOBS is not set
|
||||
# CONFIG_ESP32_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set
|
||||
# CONFIG_ESP32_USE_FIXED_STATIC_RAM_SIZE is not set
|
||||
CONFIG_ESP32_DPORT_DIS_INTERRUPT_LVL=5
|
||||
# end of ESP32-specific
|
||||
|
||||
#
|
||||
# Power Management
|
||||
#
|
||||
# CONFIG_PM_ENABLE is not set
|
||||
# end of Power Management
|
||||
|
||||
#
|
||||
# ADC-Calibration
|
||||
#
|
||||
CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y
|
||||
CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y
|
||||
CONFIG_ADC_CAL_LUT_ENABLE=y
|
||||
# end of ADC-Calibration
|
||||
|
||||
#
|
||||
# Common ESP-related
|
||||
#
|
||||
CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
||||
CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32
|
||||
CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=4096
|
||||
CONFIG_ESP_MAIN_TASK_STACK_SIZE=3584
|
||||
CONFIG_ESP_IPC_TASK_STACK_SIZE=1024
|
||||
CONFIG_ESP_IPC_USES_CALLERS_PRIORITY=y
|
||||
CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048
|
||||
CONFIG_ESP_CONSOLE_UART_DEFAULT=y
|
||||
# CONFIG_ESP_CONSOLE_UART_CUSTOM is not set
|
||||
# CONFIG_ESP_CONSOLE_UART_NONE is not set
|
||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||
CONFIG_ESP_CONSOLE_UART_TX_GPIO=1
|
||||
CONFIG_ESP_CONSOLE_UART_RX_GPIO=3
|
||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||
# CONFIG_ESP_INT_WDT is not set
|
||||
# CONFIG_ESP_TASK_WDT is not set
|
||||
# CONFIG_ESP_PANIC_HANDLER_IRAM is not set
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_BT_OFFSET=2
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y
|
||||
# end of Common ESP-related
|
||||
|
||||
#
|
||||
# Ethernet
|
||||
#
|
||||
CONFIG_ETH_ENABLED=y
|
||||
CONFIG_ETH_USE_ESP32_EMAC=y
|
||||
CONFIG_ETH_PHY_INTERFACE_RMII=y
|
||||
# CONFIG_ETH_PHY_INTERFACE_MII is not set
|
||||
CONFIG_ETH_RMII_CLK_INPUT=y
|
||||
# CONFIG_ETH_RMII_CLK_OUTPUT is not set
|
||||
CONFIG_ETH_RMII_CLK_IN_GPIO=0
|
||||
CONFIG_ETH_DMA_BUFFER_SIZE=512
|
||||
CONFIG_ETH_DMA_RX_BUFFER_NUM=10
|
||||
CONFIG_ETH_DMA_TX_BUFFER_NUM=10
|
||||
CONFIG_ETH_USE_SPI_ETHERNET=y
|
||||
# CONFIG_ETH_SPI_ETHERNET_DM9051 is not set
|
||||
# CONFIG_ETH_USE_OPENETH is not set
|
||||
# end of Ethernet
|
||||
|
||||
#
|
||||
# Event Loop Library
|
||||
#
|
||||
# CONFIG_ESP_EVENT_LOOP_PROFILING is not set
|
||||
CONFIG_ESP_EVENT_POST_FROM_ISR=y
|
||||
CONFIG_ESP_EVENT_POST_FROM_IRAM_ISR=y
|
||||
# end of Event Loop Library
|
||||
|
||||
#
|
||||
# GDB Stub
|
||||
#
|
||||
# end of GDB Stub
|
||||
|
||||
#
|
||||
# ESP HTTP client
|
||||
#
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_HTTPS is not set
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_BASIC_AUTH is not set
|
||||
# end of ESP HTTP client
|
||||
|
||||
#
|
||||
# HTTP Server
|
||||
#
|
||||
CONFIG_HTTPD_MAX_REQ_HDR_LEN=512
|
||||
CONFIG_HTTPD_MAX_URI_LEN=512
|
||||
CONFIG_HTTPD_ERR_RESP_NO_DELAY=y
|
||||
CONFIG_HTTPD_PURGE_BUF_LEN=32
|
||||
# CONFIG_HTTPD_LOG_PURGE_DATA is not set
|
||||
# CONFIG_HTTPD_WS_SUPPORT is not set
|
||||
# end of HTTP Server
|
||||
|
||||
#
|
||||
# ESP HTTPS OTA
|
||||
#
|
||||
# CONFIG_OTA_ALLOW_HTTP is not set
|
||||
# end of ESP HTTPS OTA
|
||||
|
||||
#
|
||||
# ESP HTTPS server
|
||||
#
|
||||
# CONFIG_ESP_HTTPS_SERVER_ENABLE is not set
|
||||
# end of ESP HTTPS server
|
||||
|
||||
#
|
||||
# ESP NETIF Adapter
|
||||
#
|
||||
CONFIG_ESP_NETIF_IP_LOST_TIMER_INTERVAL=120
|
||||
CONFIG_ESP_NETIF_TCPIP_LWIP=y
|
||||
# CONFIG_ESP_NETIF_LOOPBACK is not set
|
||||
CONFIG_ESP_NETIF_TCPIP_ADAPTER_COMPATIBLE_LAYER=y
|
||||
# end of ESP NETIF Adapter
|
||||
|
||||
#
|
||||
# ESP System Settings
|
||||
#
|
||||
# CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set
|
||||
CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y
|
||||
# CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set
|
||||
# CONFIG_ESP_SYSTEM_PANIC_GDBSTUB is not set
|
||||
# end of ESP System Settings
|
||||
|
||||
#
|
||||
# High resolution timer (esp_timer)
|
||||
#
|
||||
# CONFIG_ESP_TIMER_PROFILING is not set
|
||||
CONFIG_ESP_TIMER_TASK_STACK_SIZE=3584
|
||||
# CONFIG_ESP_TIMER_IMPL_FRC2 is not set
|
||||
CONFIG_ESP_TIMER_IMPL_TG0_LAC=y
|
||||
# end of High resolution timer (esp_timer)
|
||||
|
||||
#
|
||||
# Wi-Fi
|
||||
#
|
||||
CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM=16
|
||||
CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=64
|
||||
# CONFIG_ESP32_WIFI_STATIC_TX_BUFFER is not set
|
||||
CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y
|
||||
CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1
|
||||
CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=64
|
||||
# CONFIG_ESP32_WIFI_CSI_ENABLED is not set
|
||||
CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_TX_BA_WIN=32
|
||||
CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_RX_BA_WIN=32
|
||||
CONFIG_ESP32_WIFI_NVS_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y
|
||||
# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set
|
||||
CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752
|
||||
CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32
|
||||
# CONFIG_ESP32_WIFI_DEBUG_LOG_ENABLE is not set
|
||||
CONFIG_ESP32_WIFI_IRAM_OPT=y
|
||||
CONFIG_ESP32_WIFI_RX_IRAM_OPT=y
|
||||
CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y
|
||||
# end of Wi-Fi
|
||||
|
||||
#
|
||||
# PHY
|
||||
#
|
||||
CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y
|
||||
# CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set
|
||||
CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20
|
||||
CONFIG_ESP32_PHY_MAX_TX_POWER=20
|
||||
# end of PHY
|
||||
|
||||
#
|
||||
# Core dump
|
||||
#
|
||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set
|
||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set
|
||||
CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y
|
||||
# end of Core dump
|
||||
|
||||
#
|
||||
# FAT Filesystem support
|
||||
#
|
||||
# CONFIG_FATFS_CODEPAGE_DYNAMIC is not set
|
||||
CONFIG_FATFS_CODEPAGE_437=y
|
||||
# CONFIG_FATFS_CODEPAGE_720 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_737 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_771 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_775 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_850 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_852 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_855 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_857 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_860 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_861 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_862 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_863 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_864 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_865 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_866 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_869 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_932 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_936 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_949 is not set
|
||||
# CONFIG_FATFS_CODEPAGE_950 is not set
|
||||
CONFIG_FATFS_CODEPAGE=437
|
||||
CONFIG_FATFS_LFN_NONE=y
|
||||
# CONFIG_FATFS_LFN_HEAP is not set
|
||||
# CONFIG_FATFS_LFN_STACK is not set
|
||||
CONFIG_FATFS_FS_LOCK=0
|
||||
CONFIG_FATFS_TIMEOUT_MS=10000
|
||||
CONFIG_FATFS_PER_FILE_CACHE=y
|
||||
# end of FAT Filesystem support
|
||||
|
||||
#
|
||||
# Modbus configuration
|
||||
#
|
||||
CONFIG_FMB_COMM_MODE_RTU_EN=y
|
||||
CONFIG_FMB_COMM_MODE_ASCII_EN=y
|
||||
CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150
|
||||
CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200
|
||||
CONFIG_FMB_QUEUE_LENGTH=20
|
||||
CONFIG_FMB_SERIAL_TASK_STACK_SIZE=2048
|
||||
CONFIG_FMB_SERIAL_BUF_SIZE=256
|
||||
CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8
|
||||
CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000
|
||||
CONFIG_FMB_SERIAL_TASK_PRIO=10
|
||||
# CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT is not set
|
||||
CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20
|
||||
CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20
|
||||
CONFIG_FMB_CONTROLLER_STACK_SIZE=4096
|
||||
CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20
|
||||
CONFIG_FMB_TIMER_PORT_ENABLED=y
|
||||
CONFIG_FMB_TIMER_GROUP=0
|
||||
CONFIG_FMB_TIMER_INDEX=0
|
||||
# CONFIG_FMB_TIMER_ISR_IN_IRAM is not set
|
||||
# end of Modbus configuration
|
||||
|
||||
#
|
||||
# FreeRTOS
|
||||
#
|
||||
# CONFIG_FREERTOS_UNICORE is not set
|
||||
CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_FREERTOS_CORETIMER_0=y
|
||||
# CONFIG_FREERTOS_CORETIMER_1 is not set
|
||||
CONFIG_FREERTOS_HZ=1000
|
||||
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set
|
||||
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=y
|
||||
# CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK is not set
|
||||
CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y
|
||||
CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=1
|
||||
CONFIG_FREERTOS_ASSERT_FAIL_ABORT=y
|
||||
# CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE is not set
|
||||
# CONFIG_FREERTOS_ASSERT_DISABLE is not set
|
||||
CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536
|
||||
CONFIG_FREERTOS_ISR_STACKSIZE=1536
|
||||
# CONFIG_FREERTOS_LEGACY_HOOKS is not set
|
||||
CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16
|
||||
# CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION is not set
|
||||
CONFIG_FREERTOS_TIMER_TASK_PRIORITY=1
|
||||
CONFIG_FREERTOS_TIMER_TASK_STACK_DEPTH=2048
|
||||
CONFIG_FREERTOS_TIMER_QUEUE_LENGTH=10
|
||||
CONFIG_FREERTOS_QUEUE_REGISTRY_SIZE=0
|
||||
# CONFIG_FREERTOS_USE_TRACE_FACILITY is not set
|
||||
# CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS is not set
|
||||
CONFIG_FREERTOS_CHECK_MUTEX_GIVEN_BY_OWNER=y
|
||||
# CONFIG_FREERTOS_CHECK_PORT_CRITICAL_COMPLIANCE is not set
|
||||
CONFIG_FREERTOS_DEBUG_OCDAWARE=y
|
||||
# CONFIG_FREERTOS_FPU_IN_ISR is not set
|
||||
# end of FreeRTOS
|
||||
|
||||
#
|
||||
# Heap memory debugging
|
||||
#
|
||||
CONFIG_HEAP_POISONING_DISABLED=y
|
||||
# CONFIG_HEAP_POISONING_LIGHT is not set
|
||||
# CONFIG_HEAP_POISONING_COMPREHENSIVE is not set
|
||||
CONFIG_HEAP_TRACING_OFF=y
|
||||
# CONFIG_HEAP_TRACING_STANDALONE is not set
|
||||
# CONFIG_HEAP_TRACING_TOHOST is not set
|
||||
# CONFIG_HEAP_ABORT_WHEN_ALLOCATION_FAILS is not set
|
||||
# end of Heap memory debugging
|
||||
|
||||
#
|
||||
# jsmn
|
||||
#
|
||||
# CONFIG_JSMN_PARENT_LINKS is not set
|
||||
# CONFIG_JSMN_STRICT is not set
|
||||
# end of jsmn
|
||||
|
||||
#
|
||||
# libsodium
|
||||
#
|
||||
# end of libsodium
|
||||
|
||||
#
|
||||
# Log output
|
||||
#
|
||||
# CONFIG_LOG_DEFAULT_LEVEL_NONE is not set
|
||||
# CONFIG_LOG_DEFAULT_LEVEL_ERROR is not set
|
||||
# CONFIG_LOG_DEFAULT_LEVEL_WARN is not set
|
||||
CONFIG_LOG_DEFAULT_LEVEL_INFO=y
|
||||
# CONFIG_LOG_DEFAULT_LEVEL_DEBUG is not set
|
||||
# CONFIG_LOG_DEFAULT_LEVEL_VERBOSE is not set
|
||||
CONFIG_LOG_DEFAULT_LEVEL=3
|
||||
CONFIG_LOG_COLORS=y
|
||||
CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y
|
||||
# CONFIG_LOG_TIMESTAMP_SOURCE_SYSTEM is not set
|
||||
# end of Log output
|
||||
|
||||
#
|
||||
# LWIP
|
||||
#
|
||||
CONFIG_LWIP_LOCAL_HOSTNAME="esp32-dap"
|
||||
CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y
|
||||
# CONFIG_LWIP_L2_TO_L3_COPY is not set
|
||||
CONFIG_LWIP_IRAM_OPTIMIZATION=y
|
||||
CONFIG_LWIP_TIMERS_ONDEMAND=y
|
||||
CONFIG_LWIP_MAX_SOCKETS=10
|
||||
# CONFIG_LWIP_USE_ONLY_LWIP_SELECT is not set
|
||||
# CONFIG_LWIP_SO_LINGER is not set
|
||||
CONFIG_LWIP_SO_REUSE=y
|
||||
CONFIG_LWIP_SO_REUSE_RXTOALL=y
|
||||
# CONFIG_LWIP_SO_RCVBUF is not set
|
||||
# CONFIG_LWIP_NETBUF_RECVINFO is not set
|
||||
CONFIG_LWIP_IP4_FRAG=y
|
||||
CONFIG_LWIP_IP6_FRAG=y
|
||||
# CONFIG_LWIP_IP4_REASSEMBLY is not set
|
||||
# CONFIG_LWIP_IP6_REASSEMBLY is not set
|
||||
# CONFIG_LWIP_IP_FORWARD is not set
|
||||
# CONFIG_LWIP_STATS is not set
|
||||
# CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set
|
||||
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
||||
CONFIG_LWIP_GARP_TMR_INTERVAL=60
|
||||
CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=50
|
||||
CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y
|
||||
# CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set
|
||||
|
||||
#
|
||||
# DHCP server
|
||||
#
|
||||
CONFIG_LWIP_DHCPS_LEASE_UNIT=60
|
||||
CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8
|
||||
# end of DHCP server
|
||||
|
||||
# CONFIG_LWIP_AUTOIP is not set
|
||||
# CONFIG_LWIP_IPV6_AUTOCONFIG is not set
|
||||
CONFIG_LWIP_NETIF_LOOPBACK=y
|
||||
CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8
|
||||
|
||||
#
|
||||
# TCP
|
||||
#
|
||||
CONFIG_LWIP_MAX_ACTIVE_TCP=16
|
||||
CONFIG_LWIP_MAX_LISTENING_TCP=16
|
||||
CONFIG_LWIP_TCP_HIGH_SPEED_RETRANSMISSION=y
|
||||
CONFIG_LWIP_TCP_MAXRTX=12
|
||||
CONFIG_LWIP_TCP_SYNMAXRTX=12
|
||||
CONFIG_LWIP_TCP_MSS=1440
|
||||
CONFIG_LWIP_TCP_TMR_INTERVAL=250
|
||||
CONFIG_LWIP_TCP_MSL=60000
|
||||
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
|
||||
CONFIG_LWIP_TCP_WND_DEFAULT=5744
|
||||
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
||||
CONFIG_LWIP_TCP_QUEUE_OOSEQ=y
|
||||
# CONFIG_LWIP_TCP_SACK_OUT is not set
|
||||
# CONFIG_LWIP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set
|
||||
CONFIG_LWIP_TCP_OVERSIZE_MSS=y
|
||||
# CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set
|
||||
# CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set
|
||||
CONFIG_LWIP_TCP_RTO_TIME=1500
|
||||
# end of TCP
|
||||
|
||||
#
|
||||
# UDP
|
||||
#
|
||||
CONFIG_LWIP_MAX_UDP_PCBS=16
|
||||
CONFIG_LWIP_UDP_RECVMBOX_SIZE=6
|
||||
# end of UDP
|
||||
|
||||
CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=3072
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY is not set
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0=y
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x0
|
||||
# CONFIG_LWIP_PPP_SUPPORT is not set
|
||||
CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5
|
||||
|
||||
#
|
||||
# ICMP
|
||||
#
|
||||
# CONFIG_LWIP_MULTICAST_PING is not set
|
||||
# CONFIG_LWIP_BROADCAST_PING is not set
|
||||
# end of ICMP
|
||||
|
||||
#
|
||||
# LWIP RAW API
|
||||
#
|
||||
CONFIG_LWIP_MAX_RAW_PCBS=16
|
||||
# end of LWIP RAW API
|
||||
|
||||
#
|
||||
# SNTP
|
||||
#
|
||||
CONFIG_LWIP_DHCP_MAX_NTP_SERVERS=1
|
||||
CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000
|
||||
# end of SNTP
|
||||
|
||||
CONFIG_LWIP_ESP_LWIP_ASSERT=y
|
||||
# end of LWIP
|
||||
|
||||
#
|
||||
# mbedTLS
|
||||
#
|
||||
CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y
|
||||
# CONFIG_MBEDTLS_DEFAULT_MEM_ALLOC is not set
|
||||
# CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set
|
||||
CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN=y
|
||||
CONFIG_MBEDTLS_SSL_IN_CONTENT_LEN=16384
|
||||
CONFIG_MBEDTLS_SSL_OUT_CONTENT_LEN=4096
|
||||
# CONFIG_MBEDTLS_DYNAMIC_BUFFER is not set
|
||||
# CONFIG_MBEDTLS_DEBUG is not set
|
||||
|
||||
#
|
||||
# Certificate Bundle
|
||||
#
|
||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE=y
|
||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set
|
||||
# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set
|
||||
# end of Certificate Bundle
|
||||
|
||||
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
||||
# CONFIG_MBEDTLS_CMAC_C is not set
|
||||
CONFIG_MBEDTLS_HARDWARE_AES=y
|
||||
CONFIG_MBEDTLS_HARDWARE_MPI=y
|
||||
CONFIG_MBEDTLS_HARDWARE_SHA=y
|
||||
# CONFIG_MBEDTLS_ATCA_HW_ECDSA_SIGN is not set
|
||||
# CONFIG_MBEDTLS_ATCA_HW_ECDSA_VERIFY is not set
|
||||
CONFIG_MBEDTLS_HAVE_TIME=y
|
||||
# CONFIG_MBEDTLS_HAVE_TIME_DATE is not set
|
||||
CONFIG_MBEDTLS_ECDSA_DETERMINISTIC=y
|
||||
CONFIG_MBEDTLS_SHA512_C=y
|
||||
CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y
|
||||
# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set
|
||||
# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set
|
||||
# CONFIG_MBEDTLS_TLS_DISABLED is not set
|
||||
CONFIG_MBEDTLS_TLS_SERVER=y
|
||||
CONFIG_MBEDTLS_TLS_CLIENT=y
|
||||
CONFIG_MBEDTLS_TLS_ENABLED=y
|
||||
|
||||
#
|
||||
# TLS Key Exchange Methods
|
||||
#
|
||||
# CONFIG_MBEDTLS_PSK_MODES is not set
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_RSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_RSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ELLIPTIC_CURVE=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_RSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_ECDSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_ECDSA=y
|
||||
CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_RSA=y
|
||||
# end of TLS Key Exchange Methods
|
||||
|
||||
CONFIG_MBEDTLS_SSL_RENEGOTIATION=y
|
||||
# CONFIG_MBEDTLS_SSL_PROTO_SSL3 is not set
|
||||
CONFIG_MBEDTLS_SSL_PROTO_TLS1=y
|
||||
CONFIG_MBEDTLS_SSL_PROTO_TLS1_1=y
|
||||
CONFIG_MBEDTLS_SSL_PROTO_TLS1_2=y
|
||||
# CONFIG_MBEDTLS_SSL_PROTO_DTLS is not set
|
||||
CONFIG_MBEDTLS_SSL_ALPN=y
|
||||
CONFIG_MBEDTLS_CLIENT_SSL_SESSION_TICKETS=y
|
||||
CONFIG_MBEDTLS_SERVER_SSL_SESSION_TICKETS=y
|
||||
|
||||
#
|
||||
# Symmetric Ciphers
|
||||
#
|
||||
CONFIG_MBEDTLS_AES_C=y
|
||||
# CONFIG_MBEDTLS_CAMELLIA_C is not set
|
||||
# CONFIG_MBEDTLS_DES_C is not set
|
||||
CONFIG_MBEDTLS_RC4_DISABLED=y
|
||||
# CONFIG_MBEDTLS_RC4_ENABLED_NO_DEFAULT is not set
|
||||
# CONFIG_MBEDTLS_RC4_ENABLED is not set
|
||||
# CONFIG_MBEDTLS_BLOWFISH_C is not set
|
||||
# CONFIG_MBEDTLS_XTEA_C is not set
|
||||
CONFIG_MBEDTLS_CCM_C=y
|
||||
CONFIG_MBEDTLS_GCM_C=y
|
||||
# end of Symmetric Ciphers
|
||||
|
||||
# CONFIG_MBEDTLS_RIPEMD160_C is not set
|
||||
|
||||
#
|
||||
# Certificates
|
||||
#
|
||||
CONFIG_MBEDTLS_PEM_PARSE_C=y
|
||||
CONFIG_MBEDTLS_PEM_WRITE_C=y
|
||||
CONFIG_MBEDTLS_X509_CRL_PARSE_C=y
|
||||
CONFIG_MBEDTLS_X509_CSR_PARSE_C=y
|
||||
# end of Certificates
|
||||
|
||||
CONFIG_MBEDTLS_ECP_C=y
|
||||
CONFIG_MBEDTLS_ECDH_C=y
|
||||
CONFIG_MBEDTLS_ECDSA_C=y
|
||||
# CONFIG_MBEDTLS_ECJPAKE_C is not set
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP384R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP521R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP192K1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP224K1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP256K1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_BP256R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_NIST_OPTIM=y
|
||||
# CONFIG_MBEDTLS_POLY1305_C is not set
|
||||
# CONFIG_MBEDTLS_CHACHA20_C is not set
|
||||
# CONFIG_MBEDTLS_HKDF_C is not set
|
||||
# CONFIG_MBEDTLS_THREADING_C is not set
|
||||
# CONFIG_MBEDTLS_SECURITY_RISKS is not set
|
||||
# end of mbedTLS
|
||||
|
||||
#
|
||||
# mDNS
|
||||
#
|
||||
CONFIG_MDNS_MAX_SERVICES=10
|
||||
CONFIG_MDNS_TASK_PRIORITY=1
|
||||
CONFIG_MDNS_TASK_STACK_SIZE=4096
|
||||
# CONFIG_MDNS_TASK_AFFINITY_NO_AFFINITY is not set
|
||||
CONFIG_MDNS_TASK_AFFINITY_CPU0=y
|
||||
# CONFIG_MDNS_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_MDNS_TASK_AFFINITY=0x0
|
||||
CONFIG_MDNS_SERVICE_ADD_TIMEOUT_MS=2000
|
||||
CONFIG_MDNS_TIMER_PERIOD_MS=100
|
||||
# end of mDNS
|
||||
|
||||
#
|
||||
# ESP-MQTT Configurations
|
||||
#
|
||||
# CONFIG_MQTT_PROTOCOL_311 is not set
|
||||
# CONFIG_MQTT_TRANSPORT_SSL is not set
|
||||
# CONFIG_MQTT_TRANSPORT_WEBSOCKET is not set
|
||||
# CONFIG_MQTT_USE_CUSTOM_CONFIG is not set
|
||||
# CONFIG_MQTT_TASK_CORE_SELECTION_ENABLED is not set
|
||||
# CONFIG_MQTT_CUSTOM_OUTBOX is not set
|
||||
# end of ESP-MQTT Configurations
|
||||
|
||||
#
|
||||
# Newlib
|
||||
#
|
||||
CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y
|
||||
# CONFIG_NEWLIB_STDOUT_LINE_ENDING_LF is not set
|
||||
# CONFIG_NEWLIB_STDOUT_LINE_ENDING_CR is not set
|
||||
# CONFIG_NEWLIB_STDIN_LINE_ENDING_CRLF is not set
|
||||
# CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set
|
||||
CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y
|
||||
# CONFIG_NEWLIB_NANO_FORMAT is not set
|
||||
# end of Newlib
|
||||
|
||||
#
|
||||
# NVS
|
||||
#
|
||||
# end of NVS
|
||||
|
||||
#
|
||||
# OpenSSL
|
||||
#
|
||||
# CONFIG_OPENSSL_DEBUG is not set
|
||||
# CONFIG_OPENSSL_ASSERT_DO_NOTHING is not set
|
||||
CONFIG_OPENSSL_ASSERT_EXIT=y
|
||||
# end of OpenSSL
|
||||
|
||||
#
|
||||
# PThreads
|
||||
#
|
||||
CONFIG_PTHREAD_TASK_PRIO_DEFAULT=5
|
||||
CONFIG_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072
|
||||
CONFIG_PTHREAD_STACK_MIN=768
|
||||
CONFIG_PTHREAD_DEFAULT_CORE_NO_AFFINITY=y
|
||||
# CONFIG_PTHREAD_DEFAULT_CORE_0 is not set
|
||||
# CONFIG_PTHREAD_DEFAULT_CORE_1 is not set
|
||||
CONFIG_PTHREAD_TASK_CORE_DEFAULT=-1
|
||||
CONFIG_PTHREAD_TASK_NAME_DEFAULT="pthread"
|
||||
# end of PThreads
|
||||
|
||||
#
|
||||
# SPI Flash driver
|
||||
#
|
||||
# CONFIG_SPI_FLASH_VERIFY_WRITE is not set
|
||||
# CONFIG_SPI_FLASH_ENABLE_COUNTERS is not set
|
||||
CONFIG_SPI_FLASH_ROM_DRIVER_PATCH=y
|
||||
CONFIG_SPI_FLASH_DANGEROUS_WRITE_ABORTS=y
|
||||
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set
|
||||
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set
|
||||
# CONFIG_SPI_FLASH_USE_LEGACY_IMPL is not set
|
||||
# CONFIG_SPI_FLASH_SHARE_SPI1_BUS is not set
|
||||
# CONFIG_SPI_FLASH_BYPASS_BLOCK_ERASE is not set
|
||||
CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y
|
||||
CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=20
|
||||
CONFIG_SPI_FLASH_ERASE_YIELD_TICKS=1
|
||||
|
||||
#
|
||||
# Auto-detect flash chips
|
||||
#
|
||||
CONFIG_SPI_FLASH_SUPPORT_ISSI_CHIP=y
|
||||
CONFIG_SPI_FLASH_SUPPORT_MXIC_CHIP=y
|
||||
CONFIG_SPI_FLASH_SUPPORT_GD_CHIP=y
|
||||
# end of Auto-detect flash chips
|
||||
# end of SPI Flash driver
|
||||
|
||||
#
|
||||
# SPIFFS Configuration
|
||||
#
|
||||
CONFIG_SPIFFS_MAX_PARTITIONS=3
|
||||
|
||||
#
|
||||
# SPIFFS Cache Configuration
|
||||
#
|
||||
CONFIG_SPIFFS_CACHE=y
|
||||
CONFIG_SPIFFS_CACHE_WR=y
|
||||
# CONFIG_SPIFFS_CACHE_STATS is not set
|
||||
# end of SPIFFS Cache Configuration
|
||||
|
||||
CONFIG_SPIFFS_PAGE_CHECK=y
|
||||
CONFIG_SPIFFS_GC_MAX_RUNS=10
|
||||
# CONFIG_SPIFFS_GC_STATS is not set
|
||||
CONFIG_SPIFFS_PAGE_SIZE=256
|
||||
CONFIG_SPIFFS_OBJ_NAME_LEN=32
|
||||
# CONFIG_SPIFFS_FOLLOW_SYMLINKS is not set
|
||||
CONFIG_SPIFFS_USE_MAGIC=y
|
||||
CONFIG_SPIFFS_USE_MAGIC_LENGTH=y
|
||||
CONFIG_SPIFFS_META_LENGTH=4
|
||||
CONFIG_SPIFFS_USE_MTIME=y
|
||||
|
||||
#
|
||||
# Debug Configuration
|
||||
#
|
||||
# CONFIG_SPIFFS_DBG is not set
|
||||
# CONFIG_SPIFFS_API_DBG is not set
|
||||
# CONFIG_SPIFFS_GC_DBG is not set
|
||||
# CONFIG_SPIFFS_CACHE_DBG is not set
|
||||
# CONFIG_SPIFFS_CHECK_DBG is not set
|
||||
# CONFIG_SPIFFS_TEST_VISUALISATION is not set
|
||||
# end of Debug Configuration
|
||||
# end of SPIFFS Configuration
|
||||
|
||||
#
|
||||
# TinyUSB
|
||||
#
|
||||
|
||||
#
|
||||
# Descriptor configuration
|
||||
#
|
||||
CONFIG_USB_DESC_CUSTOM_VID=0x1234
|
||||
CONFIG_USB_DESC_CUSTOM_PID=0x5678
|
||||
# end of Descriptor configuration
|
||||
# end of TinyUSB
|
||||
|
||||
#
|
||||
# Unity unit testing library
|
||||
#
|
||||
CONFIG_UNITY_ENABLE_FLOAT=y
|
||||
CONFIG_UNITY_ENABLE_DOUBLE=y
|
||||
# CONFIG_UNITY_ENABLE_COLOR is not set
|
||||
CONFIG_UNITY_ENABLE_IDF_TEST_RUNNER=y
|
||||
# CONFIG_UNITY_ENABLE_FIXTURE is not set
|
||||
# CONFIG_UNITY_ENABLE_BACKTRACE_ON_FAIL is not set
|
||||
# end of Unity unit testing library
|
||||
|
||||
#
|
||||
# Virtual file system
|
||||
#
|
||||
CONFIG_VFS_SUPPORT_IO=y
|
||||
CONFIG_VFS_SUPPORT_DIR=y
|
||||
CONFIG_VFS_SUPPORT_SELECT=y
|
||||
CONFIG_VFS_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||
CONFIG_VFS_SUPPORT_TERMIOS=y
|
||||
|
||||
#
|
||||
# Host File System I/O (Semihosting)
|
||||
#
|
||||
CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||
CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||
# end of Host File System I/O (Semihosting)
|
||||
# end of Virtual file system
|
||||
|
||||
#
|
||||
# Wear Levelling
|
||||
#
|
||||
# CONFIG_WL_SECTOR_SIZE_512 is not set
|
||||
CONFIG_WL_SECTOR_SIZE_4096=y
|
||||
CONFIG_WL_SECTOR_SIZE=4096
|
||||
# end of Wear Levelling
|
||||
|
||||
#
|
||||
# Wi-Fi Provisioning Manager
|
||||
#
|
||||
CONFIG_WIFI_PROV_SCAN_MAX_ENTRIES=16
|
||||
CONFIG_WIFI_PROV_AUTOSTOP_TIMEOUT=30
|
||||
# end of Wi-Fi Provisioning Manager
|
||||
|
||||
#
|
||||
# Supplicant
|
||||
#
|
||||
CONFIG_WPA_MBEDTLS_CRYPTO=y
|
||||
# CONFIG_WPA_DEBUG_PRINT is not set
|
||||
# CONFIG_WPA_TESTING_OPTIONS is not set
|
||||
# CONFIG_WPA_WPS_WARS is not set
|
||||
# end of Supplicant
|
||||
# end of Component config
|
||||
|
||||
#
|
||||
# Compatibility options
|
||||
#
|
||||
# CONFIG_LEGACY_INCLUDE_COMMON_HEADERS is not set
|
||||
# end of Compatibility options
|
Loading…
Reference in New Issue