3
.gitignore
vendored
Normal file → Executable file
3
.gitignore
vendored
Normal file → Executable file
@@ -10,7 +10,8 @@
|
||||
CMakeFiles/
|
||||
cmake-build-debug/
|
||||
build/
|
||||
|
||||
sdkconfig
|
||||
sdkconfig.old
|
||||
CMakeCache.txt
|
||||
cmake-build-debug/.ninja_deps
|
||||
cmake-build-debug/.ninja_log
|
||||
|
||||
0
CMakeLists.txt
Normal file → Executable file
0
CMakeLists.txt
Normal file → Executable file
0
components/ssd1306/CMakeLists.txt
Normal file → Executable file
0
components/ssd1306/CMakeLists.txt
Normal file → Executable file
2
components/ssd1306/Kconfig.projbuild
Normal file → Executable file
2
components/ssd1306/Kconfig.projbuild
Normal file → Executable file
@@ -132,7 +132,7 @@ menu "SSD1306 Configuration"
|
||||
config RESET_GPIO
|
||||
int "RESET GPIO number"
|
||||
range -1 GPIO_RANGE_MAX
|
||||
default 15 if IDF_TARGET_ESP32
|
||||
default -1 if IDF_TARGET_ESP32
|
||||
default 38 if IDF_TARGET_ESP32S2 || IDF_TARGET_ESP32S3
|
||||
default 4 # C3 and others
|
||||
help
|
||||
|
||||
0
components/ssd1306/include/font8x8_basic.h
Normal file → Executable file
0
components/ssd1306/include/font8x8_basic.h
Normal file → Executable file
0
components/ssd1306/include/ssd1306.h
Normal file → Executable file
0
components/ssd1306/include/ssd1306.h
Normal file → Executable file
0
components/ssd1306/ssd1306.c
Normal file → Executable file
0
components/ssd1306/ssd1306.c
Normal file → Executable file
0
components/ssd1306/ssd1306_i2c_legacy.c
Normal file → Executable file
0
components/ssd1306/ssd1306_i2c_legacy.c
Normal file → Executable file
0
components/ssd1306/ssd1306_i2c_new.c
Normal file → Executable file
0
components/ssd1306/ssd1306_i2c_new.c
Normal file → Executable file
0
components/ssd1306/ssd1306_spi.c
Normal file → Executable file
0
components/ssd1306/ssd1306_spi.c
Normal file → Executable file
2
dependencies.lock
Normal file → Executable file
2
dependencies.lock
Normal file → Executable file
@@ -2,7 +2,7 @@ dependencies:
|
||||
idf:
|
||||
source:
|
||||
type: idf
|
||||
version: 5.2.3
|
||||
version: 5.3.0
|
||||
manifest_hash: 482e2222071e855d99a96f5a61a37a4f589f24e7994d6610de1e65027e5a15a9
|
||||
target: esp32
|
||||
version: 2.0.0
|
||||
|
||||
3
generate_pins_header.py
Normal file → Executable file
3
generate_pins_header.py
Normal file → Executable file
@@ -26,7 +26,7 @@ with open(sdkconfig_path, "r") as f:
|
||||
|
||||
# Header-Datei erzeugen
|
||||
with open(header_path, "w") as header:
|
||||
header.write("// Automatically generated file. Do not modify.\n\n")
|
||||
header.write("// Automatically generated file. Do not modify.\n#ifndef PARSED_PINS_H\n#define PARSED_PINS_H\n\n")
|
||||
|
||||
for config_var, pin1_name, pin2_name, pin3_name in config_entries:
|
||||
# Suche nach dem Konfigurationswert
|
||||
@@ -47,5 +47,6 @@ with open(header_path, "w") as header:
|
||||
print(f"Parsed {config_var}: {pins[0].strip()}, {pins[1].strip()}, {pins[2].strip()}")
|
||||
else:
|
||||
print(f"Warning: {config_var} not found in sdkconfig")
|
||||
header.write("#endif")
|
||||
|
||||
print(f"Header file '{header_path}' generated successfully.")
|
||||
|
||||
100
main/ADC.c
Executable file
100
main/ADC.c
Executable file
@@ -0,0 +1,100 @@
|
||||
#include "ADC.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "esp_adc/adc_cali.h"
|
||||
#include "esp_adc/adc_cali_scheme.h"
|
||||
#include "esp_log.h"
|
||||
#include "parsed_pins.h"
|
||||
#include "esp_adc/adc_oneshot.h"
|
||||
|
||||
static portMUX_TYPE mux = portMUX_INITIALIZER_UNLOCKED;
|
||||
static adc_cali_handle_t cali_handle = NULL;
|
||||
static adc_oneshot_unit_handle_t adc1_handle = NULL;
|
||||
|
||||
/*############################################*/
|
||||
/*################ ADC-Setup #################*/
|
||||
/*############################################*/
|
||||
void configure_ADC1()
|
||||
{
|
||||
// ADC1 Initialisierung
|
||||
adc_oneshot_unit_init_cfg_t init_config = {
|
||||
.unit_id = ADC_UNIT_1,
|
||||
.ulp_mode = ADC_ULP_MODE_DISABLE,
|
||||
};
|
||||
ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc1_handle));
|
||||
|
||||
// Kanal-Konfiguration
|
||||
adc_oneshot_chan_cfg_t config = {
|
||||
.bitwidth = ADC_BITWIDTH_DEFAULT,
|
||||
.atten = ADC_ATTEN_DB_12,
|
||||
};
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_TORQUE_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_U_SENSE_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_I_SENSE_U_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_I_SENSE_V_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_I_SENSE_W_ADC, &config));
|
||||
|
||||
// Kalibrierung initialisieren
|
||||
adc_cali_line_fitting_config_t cali_config = {
|
||||
.atten = ADC_ATTEN_DB_12,
|
||||
.bitwidth = ADC_BITWIDTH_DEFAULT,
|
||||
};
|
||||
|
||||
esp_err_t ret = adc_cali_create_scheme_line_fitting(&cali_config, &cali_handle);
|
||||
if (ret == ESP_OK) {
|
||||
ESP_LOGI("ADC", "ADC-Kalibrierung erfolgreich initialisiert");
|
||||
} else {
|
||||
ESP_LOGW("ADC", "ADC-Kalibrierung nicht möglich, Rohwerte werden verwendet");
|
||||
cali_handle = NULL; // Keine Kalibrierung verfügbar
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static uint32_t read_voltage(int channel) {
|
||||
int adc_raw = 0;
|
||||
int voltage_calibrated = 0; // Verwende int für die Kalibrierungsfunktion
|
||||
uint32_t voltage = 0; // Konvertiere später zu uint32_t
|
||||
|
||||
// ADC-Rohwert lesen
|
||||
ESP_ERROR_CHECK(adc_oneshot_read(adc1_handle, channel, &adc_raw));
|
||||
|
||||
// Kalibrierung anwenden, falls verfügbar
|
||||
if (cali_handle) {
|
||||
ESP_ERROR_CHECK(adc_cali_raw_to_voltage(cali_handle, adc_raw, &voltage_calibrated));
|
||||
voltage = (uint32_t) voltage_calibrated; // Konvertiere zu uint32_t
|
||||
} else {
|
||||
voltage = adc_raw; // Fallback auf Rohwert
|
||||
}
|
||||
|
||||
return voltage;
|
||||
}
|
||||
|
||||
// Funktion zur Umrechnung in spezifische Spannung
|
||||
uint32_t get_voltage_in()
|
||||
{
|
||||
uint32_t adc_voltage = read_voltage(CONFIG_U_SENSE_ADC);
|
||||
ESP_LOGI("ADC", "ADC%d:voltage:%ld", CONFIG_U_SENSE_ADC, adc_voltage);
|
||||
uint32_t voltage_in = adc_voltage / 0.0909;
|
||||
return voltage_in;
|
||||
}
|
||||
|
||||
int32_t get_current_ASC712(int ADC_pin)
|
||||
{
|
||||
int32_t adc_voltage = read_voltage(ADC_pin);
|
||||
int32_t current = (adc_voltage +184)/(10.0/12)-2500;
|
||||
ESP_LOGI("ADC", "ADC%d:voltage:%ldcurrent%ld", ADC_pin, adc_voltage, current);
|
||||
return current;
|
||||
}
|
||||
|
||||
uint32_t get_torque()
|
||||
{
|
||||
uint32_t adc_voltage =read_voltage(CONFIG_TORQUE_ADC);
|
||||
uint32_t torque = adc_voltage/33;
|
||||
|
||||
return torque;
|
||||
}
|
||||
int32_t get_current_bridge(int ADC_pin){
|
||||
int32_t adc_voltage = read_voltage(ADC_pin);
|
||||
ESP_LOGI("CurrentBridge", "ADC:%ld",adc_voltage);
|
||||
int32_t current = ((adc_voltage- 142)/6.77)/0.007;
|
||||
return current;
|
||||
}
|
||||
4
main/CMakeLists.txt
Normal file → Executable file
4
main/CMakeLists.txt
Normal file → Executable file
@@ -1,3 +1,3 @@
|
||||
idf_component_register(SRCS "functions.c" "app_main.c"
|
||||
idf_component_register(SRCS "menu.c" "ADC.c" "GPIO.c" "mcpwm.c" "functions.c" "app_main.c"
|
||||
INCLUDE_DIRS "include""${CMAKE_SOURCE_DIR}""."
|
||||
REQUIRES ssd1306 driver esp_adc)
|
||||
REQUIRES ssd1306 driver esp_adc hal esp_timer)
|
||||
|
||||
219
main/GPIO.c
Executable file
219
main/GPIO.c
Executable file
@@ -0,0 +1,219 @@
|
||||
#include "GPIO.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "parsed_pins.h"
|
||||
#include "esp_log.h"
|
||||
#include "sdkconfig.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "esp_timer.h"
|
||||
#include "driver/uart.h"
|
||||
#include "soc/io_mux_reg.h"
|
||||
//external Encoder
|
||||
static void IRAM_ATTR index_isr_handler(void *arg);
|
||||
static void IRAM_ATTR enc_ab_isr_handler(void *arg);
|
||||
|
||||
static volatile int64_t delta_index_time = 0;
|
||||
static volatile int64_t last_index_time = 0;
|
||||
static volatile int64_t delta_AB_time = 0;
|
||||
static volatile int64_t last_AB_time = 0;
|
||||
|
||||
static volatile int16_t enc_in_counter = 0;
|
||||
static volatile int64_t last_interrupt_time = 0;
|
||||
static volatile uint16_t last_interrupt_time_but = 0;
|
||||
static volatile bool enc_in_button_state = false;
|
||||
static volatile uint8_t last_state = 0;
|
||||
|
||||
/*############################################*/
|
||||
/*############### GPIO-Setup #################*/
|
||||
/*############################################*/
|
||||
|
||||
void configure_GPIO_dir()
|
||||
{
|
||||
/* reset every used GPIO-pin */
|
||||
uart_driver_delete(UART_NUM_0);
|
||||
// GPIO1 als GPIO konfigurieren (anstatt als UART0 TX)
|
||||
PIN_FUNC_SELECT(IO_MUX_GPIO1_REG, PIN_FUNC_GPIO);
|
||||
|
||||
// GPIO3 als GPIO konfigurieren (anstatt als UART0 RX)
|
||||
PIN_FUNC_SELECT(IO_MUX_GPIO3_REG, PIN_FUNC_GPIO);
|
||||
|
||||
gpio_reset_pin(CONFIG_HALL_A_GPIO);
|
||||
gpio_reset_pin(CONFIG_HALL_B_GPIO);
|
||||
gpio_reset_pin(CONFIG_HALL_C_GPIO);
|
||||
|
||||
gpio_reset_pin(CONFIG_IN_ENC_A_GPIO);
|
||||
gpio_reset_pin(CONFIG_IN_ENC_B_GPIO);
|
||||
gpio_reset_pin(CONFIG_IN_ENC_BUT_GPIO);
|
||||
|
||||
|
||||
gpio_reset_pin(CONFIG_EXT_ENC_LEFT_GPIO);
|
||||
gpio_reset_pin(CONFIG_EXT_ENC_RIGHT_GPIO);
|
||||
|
||||
gpio_reset_pin(CONFIG_RFE_GPIO);
|
||||
gpio_config_t io_conf_RFE = {};
|
||||
io_conf_RFE.intr_type = GPIO_INTR_DISABLE; // Keine Interrupts
|
||||
io_conf_RFE.mode = GPIO_MODE_INPUT; // Als Eingang setzen
|
||||
io_conf_RFE.pin_bit_mask = (1ULL << CONFIG_RFE_GPIO); // Pin festlegen
|
||||
io_conf_RFE.pull_down_en = GPIO_PULLDOWN_DISABLE;
|
||||
io_conf_RFE.pull_up_en = GPIO_PULLUP_DISABLE; // Pull-up-Widerstand deaktivieren
|
||||
gpio_config(&io_conf_RFE);
|
||||
|
||||
/* Set the GPIO as a push/pull output*/
|
||||
|
||||
|
||||
gpio_set_direction(CONFIG_HALL_A_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_HALL_B_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_HALL_C_GPIO, GPIO_MODE_INPUT);
|
||||
|
||||
gpio_set_direction(CONFIG_IN_ENC_A_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_IN_ENC_B_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_pull_mode(CONFIG_IN_ENC_A_GPIO, GPIO_PULLUP_ENABLE);
|
||||
gpio_set_pull_mode(CONFIG_IN_ENC_B_GPIO, GPIO_PULLUP_ENABLE);
|
||||
gpio_set_direction(CONFIG_IN_ENC_BUT_GPIO, GPIO_MODE_INPUT);
|
||||
|
||||
|
||||
gpio_set_direction(CONFIG_EXT_ENC_LEFT_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_EXT_ENC_RIGHT_GPIO, GPIO_MODE_INPUT);
|
||||
|
||||
|
||||
ESP_LOGI("GPIO", "configured for DIY power PCB");
|
||||
|
||||
gpio_config_t io_conf = {};
|
||||
io_conf.pin_bit_mask = (1ULL << CONFIG_EXT_ENC_INDX_GPIO)| (1ULL << CONFIG_HALL_A_GPIO)| (1ULL << CONFIG_IN_ENC_A_GPIO)| (1ULL << CONFIG_IN_ENC_B_GPIO);
|
||||
io_conf.mode = GPIO_MODE_INPUT;
|
||||
io_conf.pull_up_en = GPIO_PULLUP_ENABLE;
|
||||
io_conf.intr_type = GPIO_INTR_ANYEDGE; // Interrupt auf beiden Flanken
|
||||
gpio_config(&io_conf);
|
||||
|
||||
|
||||
|
||||
gpio_config_t io_conf_negedge = {};
|
||||
io_conf_negedge.pin_bit_mask = (1ULL << CONFIG_IN_ENC_BUT_GPIO);
|
||||
io_conf_negedge.mode = GPIO_MODE_INPUT;
|
||||
io_conf_negedge.pull_up_en = GPIO_PULLUP_ENABLE;
|
||||
io_conf_negedge.intr_type = GPIO_INTR_POSEDGE; // Interrupt nur auf positive Flanken
|
||||
gpio_config(&io_conf_negedge);
|
||||
|
||||
gpio_install_isr_service(0);
|
||||
ESP_ERROR_CHECK(gpio_isr_handler_add(CONFIG_EXT_ENC_INDX_GPIO, index_isr_handler, NULL));
|
||||
ESP_ERROR_CHECK(gpio_isr_handler_add(CONFIG_HALL_A_GPIO, enc_ab_isr_handler, NULL));
|
||||
|
||||
}
|
||||
|
||||
/*############################################*/
|
||||
/*############### Ext Encoder ################*/
|
||||
/*############################################*/
|
||||
static void IRAM_ATTR index_isr_handler(void *arg){
|
||||
uint64_t current_time = esp_timer_get_time();
|
||||
|
||||
if (last_index_time != 0){
|
||||
delta_index_time = current_time - last_index_time;
|
||||
}
|
||||
last_index_time = current_time;
|
||||
}
|
||||
static void IRAM_ATTR enc_ab_isr_handler(void *arg){
|
||||
uint64_t current_time = esp_timer_get_time();
|
||||
|
||||
if (last_AB_time != 0){
|
||||
delta_AB_time = current_time - last_AB_time;
|
||||
}
|
||||
last_AB_time = current_time;
|
||||
}
|
||||
|
||||
float get_speed_index(){
|
||||
uint64_t local_delta_time = delta_index_time;
|
||||
float speed_rpm = 0;
|
||||
if (local_delta_time>0){
|
||||
speed_rpm = (60.0*1000000.0/local_delta_time);
|
||||
ESP_LOGI("Encoder", "Geschwindigkeit_Indx: %.2f RPM", speed_rpm);
|
||||
}
|
||||
return speed_rpm;
|
||||
}
|
||||
float get_speed_AB(){
|
||||
uint64_t local_delta_time = delta_AB_time;
|
||||
float speed_rpm = 0;
|
||||
if (local_delta_time>0){
|
||||
speed_rpm = (60.0*1000000.0/local_delta_time)/1000;
|
||||
ESP_LOGI("Encoder", "Geschwindigkeit_AB: %.2f RPM", speed_rpm);
|
||||
}
|
||||
return speed_rpm;
|
||||
}
|
||||
int get_direction(){//-1=Error,0=right,1=left
|
||||
bool right = gpio_get_level(CONFIG_EXT_ENC_RIGHT_GPIO);
|
||||
bool left = gpio_get_level(CONFIG_EXT_ENC_LEFT_GPIO);
|
||||
int direction;
|
||||
if (left && right){
|
||||
direction= -1;
|
||||
ESP_LOGI("Encoder","Direction: Error");
|
||||
}else if(right){
|
||||
direction = 0;
|
||||
ESP_LOGI("Encoder","Direction: Right");
|
||||
}else{
|
||||
direction = 1;
|
||||
ESP_LOGI("Encoder","Direction: Left");
|
||||
}
|
||||
return direction;
|
||||
|
||||
}
|
||||
|
||||
|
||||
/*############################################*/
|
||||
/*############ Internal Encoder ##############*/
|
||||
/*############################################*
|
||||
|
||||
static void IRAM_ATTR enc_in_isr_handler(void *arg) {
|
||||
static uint64_t last_interrupt_time = 0;
|
||||
|
||||
// Aktueller Zustand der Pins lesen
|
||||
uint8_t current_state = (gpio_get_level(CONFIG_IN_ENC_A_GPIO) << 1) | gpio_get_level(CONFIG_IN_ENC_B_GPIO);
|
||||
uint64_t interrupt_time = esp_timer_get_time();
|
||||
|
||||
// Zustandswechsel-Logik (FSM) ohne starre Entprellzeit
|
||||
if (current_state != last_state) {
|
||||
// Nur wenn der Wechsel signifikant verzögert ist (gute Flanke)
|
||||
if ((interrupt_time - last_interrupt_time) > CONFIG_IN_ENCODER_DEBOUNCE_TIME) {
|
||||
if ((last_state == 0b01 && current_state == 0b11) ||
|
||||
(last_state == 0b10 && current_state == 0b00)) {
|
||||
enc_in_counter--; // Vorwärtsdrehen
|
||||
} else if ((last_state == 0b10 && current_state == 0b11) ||
|
||||
(last_state == 0b01 && current_state == 0b00)) {
|
||||
enc_in_counter++; // Rückwärtsdrehen
|
||||
}
|
||||
last_state = current_state; // Zustand aktualisieren
|
||||
last_interrupt_time = interrupt_time;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void IRAM_ATTR enc_in_but_isr_handler(void *arg) {
|
||||
uint64_t interrupt_time = esp_timer_get_time();
|
||||
|
||||
// Entprellung: Verhindert die Erfassung von Störungen aufgrund von Prellung
|
||||
if (interrupt_time - last_interrupt_time_but > (CONFIG_IN_ENCODER_DEBOUNCE_TIME*1000)) { // Entprellungszeit
|
||||
last_interrupt_time_but = interrupt_time; // Entprellzeit zurücksetzen
|
||||
// Bestimmen der Richtung anhand des Zustands von Pin A und B
|
||||
if (gpio_get_level(CONFIG_IN_ENC_A_GPIO)) {
|
||||
enc_in_button_state = true;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
int16_t get_enc_in_counter(){
|
||||
ESP_LOGI("Encoder_Int","Counter:%i",enc_in_counter);
|
||||
return enc_in_counter;
|
||||
}
|
||||
|
||||
void set_enc_in_counter(int16_t inital_value){
|
||||
enc_in_counter = inital_value;
|
||||
}
|
||||
|
||||
bool get_enc_in_but(){
|
||||
if (enc_in_button_state){
|
||||
enc_in_button_state = false;
|
||||
return true;
|
||||
}
|
||||
else{
|
||||
return false;
|
||||
}
|
||||
}*/
|
||||
129
main/Kconfig.projbuild
Normal file → Executable file
129
main/Kconfig.projbuild
Normal file → Executable file
@@ -1,4 +1,18 @@
|
||||
menu "DIY Power PCB Configuration"
|
||||
choice Version
|
||||
prompt "Hardware Version"
|
||||
default V2
|
||||
help
|
||||
Choose Version of the used PCB
|
||||
config V2
|
||||
bool "V2"
|
||||
help
|
||||
second Rev. of the DIY Power PCB
|
||||
config V1
|
||||
bool "V1"
|
||||
help
|
||||
first rev. of the DIY power PCB
|
||||
endchoice
|
||||
|
||||
orsource "$IDF_PATH/examples/common_components/env_caps/$IDF_TARGET/Kconfig.env_caps"
|
||||
menu "ADC 1 configurations"
|
||||
@@ -17,7 +31,7 @@ menu "DIY Power PCB Configuration"
|
||||
string "Current sensing ADC1 numbers of U, V, W"
|
||||
default "6, 3, 0"
|
||||
help
|
||||
ADC1 numbers of the current sensing pins at U,V and W. Write seperated by a comma. example:"34,29,36"
|
||||
ADC1 numbers of the current sensing pins at U,V and W. Write seperated by a comma. example:"34, 29, 36"
|
||||
config TORQUE_ADC
|
||||
int "Torque sensing ADC1 number"
|
||||
default 4
|
||||
@@ -30,25 +44,6 @@ menu "DIY Power PCB Configuration"
|
||||
default "26, 14, 13"
|
||||
help
|
||||
GPIO numbers of the Highside controling pins, seperate by comma!
|
||||
config ENABLE_PWM_HIN
|
||||
bool "Enable PWM for Highsides"
|
||||
default y
|
||||
help
|
||||
Enable PWM on the Highside Switches, probably mendatory because of bootstrap capacitors
|
||||
if ENABLE_PWM_HIN
|
||||
config FREQ_PWM_HIN
|
||||
int "frequency"
|
||||
range 20000 60000
|
||||
default 20000
|
||||
help
|
||||
The base Frequency of the PWM in Hz min: 20KHz max: 60KHz
|
||||
config DUTY_PWM_HIN
|
||||
int "duty cycle"
|
||||
range 0 100
|
||||
default 50
|
||||
help
|
||||
The inital duty-cycle
|
||||
endif
|
||||
endmenu
|
||||
menu "Lowside pin configurations (LIN)"
|
||||
config LIN_U_V_W_GPIO
|
||||
@@ -56,25 +51,39 @@ menu "DIY Power PCB Configuration"
|
||||
default "25, 27, 12"
|
||||
help
|
||||
GPIO numbers of the Lowside controling pins, seperate by comma!
|
||||
config ENABLE_PWM_LIN
|
||||
bool "Enable PWM for Lowsides"
|
||||
default n
|
||||
help
|
||||
Enable PWM on the Lowside Switches, probably not mendatory because of Highside PWM more important
|
||||
if ENABLE_PWM_LIN
|
||||
config FREQ_PWM_LIN
|
||||
int "frequency"
|
||||
range 20000 60000
|
||||
default 20000
|
||||
help
|
||||
The base Frequency of the PWM in Hz min: 20KHz max: 60KHz
|
||||
config DUTY_PWM_LIN
|
||||
int "duty cycle"
|
||||
range 0 100
|
||||
default 50
|
||||
help
|
||||
The inital duty-cycle
|
||||
endif
|
||||
endmenu
|
||||
menu "PWM configuration"
|
||||
config ENABLE_PWM
|
||||
bool "Enable PWM"
|
||||
default y
|
||||
help
|
||||
Enable PWM
|
||||
if ENABLE_PWM
|
||||
config TIMER_BASE_FREQ
|
||||
int "Timers Base frequency"
|
||||
range 1000000 40000000
|
||||
default 40000000
|
||||
help
|
||||
The Base Freqeuncy of the used Timer
|
||||
config FREQ_PWM
|
||||
int "frequency"
|
||||
range 20000 80000
|
||||
default 20000
|
||||
help
|
||||
The base Frequency of the PWM in Hz min: 20KHz max: 60KHz
|
||||
config DUTY_PWM
|
||||
int "duty cycle"
|
||||
range 0 100
|
||||
default 50
|
||||
help
|
||||
The inital duty-cycle in percent
|
||||
endif
|
||||
config DEAD_TIME_PWM
|
||||
int "time (ns)"
|
||||
range 0 10000
|
||||
default 0
|
||||
help
|
||||
Deadtime
|
||||
endmenu
|
||||
menu "Hall Sensor pin configurations"
|
||||
config HALL_A_B_C_GPIO
|
||||
@@ -85,17 +94,44 @@ menu "DIY Power PCB Configuration"
|
||||
endmenu
|
||||
menu "Input pin configurations"
|
||||
config IN_ENCODER_GPIO
|
||||
string "turning encoder(on board) GPIO pins: A, B, Button"
|
||||
default "3, 2, 23"
|
||||
string "Turning encoder (on board) GPIO pins: A, B, Button"
|
||||
help
|
||||
GPIO numbers of the pins connected to A,B and the button of the encoder
|
||||
GPIO numbers of the pins connected to A, B, and the button of the encoder.
|
||||
Automatically set based on the chosen hardware version.
|
||||
config IN_ENCODER_GPIO_V1
|
||||
string
|
||||
default "3, 2, 23"
|
||||
depends on V1
|
||||
|
||||
config IN_ENCODER_GPIO_V2
|
||||
string
|
||||
default "23, 1, 3"
|
||||
depends on V2
|
||||
|
||||
config IN_ENCODER_GPIO
|
||||
string
|
||||
default IN_ENCODER_GPIO_V1 if V1
|
||||
default IN_ENCODER_GPIO_V2 if V2
|
||||
|
||||
config IN_ENCODER_DEBOUNCE_TIME
|
||||
int "Debounce Time in ms"
|
||||
default "50"
|
||||
help
|
||||
debouncing time between Encoder turns
|
||||
if V1
|
||||
config BUTTON_GPIO
|
||||
int "button GPIO pin"
|
||||
default 1
|
||||
help
|
||||
GPIO number of the pin connected to the button on the pcb
|
||||
|
||||
endif
|
||||
if V2
|
||||
config ESP_LED
|
||||
int "ESP LED GPIO pin"
|
||||
default 2
|
||||
help
|
||||
GPIO number of the pin conneted to the LED on the ESP module
|
||||
endif
|
||||
config EXT_ENCODER_GPIO
|
||||
string "encoder(at motor) GPIO pins: Indx, Left, Right"
|
||||
default "16, 18, 5"
|
||||
@@ -107,12 +143,5 @@ menu "DIY Power PCB Configuration"
|
||||
help
|
||||
GPIO number of the pin connected to the RFE pin of the Bridge
|
||||
endmenu
|
||||
|
||||
config BLINK_PERIOD
|
||||
int "Blink period in ms"
|
||||
range 10 3600000
|
||||
default 1000
|
||||
help
|
||||
Define the blinking period in milliseconds.
|
||||
|
||||
endmenu
|
||||
|
||||
142
main/app_main.c
Normal file → Executable file
142
main/app_main.c
Normal file → Executable file
@@ -1,74 +1,108 @@
|
||||
/*
|
||||
This is the first try of a Test-Software for the DIY Power PCB by Fabian Zaske
|
||||
*/
|
||||
#include "functions.h"
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "GPIO.h"
|
||||
#include "mcpwm.h"
|
||||
#include "ADC.h"
|
||||
#include "string.h"
|
||||
#include "menu.h"
|
||||
#include "esp_log.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "string.h"
|
||||
#include "parsed_pins.h"
|
||||
#include "sdkconfig.h"
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
const char *TAG = "Main_test";
|
||||
|
||||
void app_main(void)
|
||||
{
|
||||
uint32_t Torque = 0;
|
||||
|
||||
|
||||
/* uint32_t Torque = 0;
|
||||
uint32_t Voltage_IN = 0;
|
||||
int32_t Current_U = 0;
|
||||
int32_t Current_V = 0;
|
||||
int32_t Current_W = 0;
|
||||
int32_t Current_bridge =0;
|
||||
int duty = 512;
|
||||
int16_t enc_counter = 0;
|
||||
bool Hall_A_On = false;
|
||||
bool Hall_B_On = false;
|
||||
bool Hall_C_On = false;
|
||||
int direction = 0;
|
||||
float Speed_indx = 0.0;
|
||||
float Speed_AB = 0.0;*/
|
||||
|
||||
bool RFE_Pulled = false;
|
||||
uint16_t menu_counter = 0;
|
||||
float duty = (float)CONFIG_DUTY_PWM;
|
||||
duty = 15.0;
|
||||
char display_message[50]; // Puffer für die Nachricht
|
||||
ESP_LOGI(TAG, "Test");
|
||||
configure_GPIO_dir(TAG);
|
||||
adc_oneshot_unit_handle_t adc1_handle = configure_ADC1(TAG);
|
||||
SSD1306_t *dev_pt = configure_OLED(TAG);
|
||||
|
||||
set_PWM_Timer();
|
||||
set_PWM();
|
||||
int i =0;
|
||||
bool enc_but_state = false;
|
||||
bool in_menu = false;
|
||||
uint16_t mcpwm_freq = CONFIG_FREQ_PWM;
|
||||
|
||||
configure_GPIO_dir();
|
||||
configure_OLED();
|
||||
config_internal_Encoder();
|
||||
mcpwm_init();
|
||||
configure_ADC1();
|
||||
|
||||
int Speed_AB = get_speed_AB();
|
||||
|
||||
//gpio_set_level(CONFIG_HIN_V_GPIO, 1);
|
||||
while (1) {
|
||||
menu_loop();
|
||||
|
||||
//ssd1306_clear_screen(dev_pt, false);
|
||||
// Die Anzeige der OLED mit der richtigen Nachricht
|
||||
Torque = get_torque(adc1_handle);
|
||||
Voltage_IN = get_voltage_in(adc1_handle);
|
||||
Current_U = get_current_ASC712(adc1_handle,CONFIG_I_SENSE_U_ADC);
|
||||
Current_V = get_current_ASC712(adc1_handle,CONFIG_I_SENSE_U_ADC);
|
||||
Current_W = get_current_ASC712(adc1_handle,CONFIG_I_SENSE_U_ADC);
|
||||
Current_bridge = get_current_bridge(adc1_handle, CONFIG_I_SENSE_ADC);
|
||||
if (Voltage_IN >= 20000){
|
||||
ssd1306_display_text(dev_pt, 1, "Bridge=ON", 10, false);
|
||||
switch (i)
|
||||
{
|
||||
case 0:
|
||||
V_U_start(duty);
|
||||
break;
|
||||
case 1:
|
||||
V_W_start(duty);
|
||||
break;
|
||||
case 2:
|
||||
U_W_start(duty);
|
||||
break;
|
||||
case 3:
|
||||
U_V_start(duty);
|
||||
break;
|
||||
case 4:
|
||||
W_V_start(duty);
|
||||
break;
|
||||
case 5:
|
||||
W_U_start(duty);
|
||||
i=0;
|
||||
break;
|
||||
/* Die Anzeige der OLED mit der richtigen Nachricht
|
||||
Torque = get_torque();
|
||||
Voltage_IN = get_voltage_in();
|
||||
Current_U = get_current_ASC712(CONFIG_I_SENSE_U_ADC);
|
||||
Current_V = get_current_ASC712(CONFIG_I_SENSE_V_ADC);
|
||||
Current_W = get_current_ASC712(CONFIG_I_SENSE_W_ADC);
|
||||
*/
|
||||
/* Hall_A_On = get_Hall(CONFIG_HALL_A_GPIO);
|
||||
Hall_B_On = get_Hall(CONFIG_HALL_B_GPIO);
|
||||
Hall_C_On = get_Hall(CONFIG_HALL_C_GPIO);
|
||||
|
||||
|
||||
//Speed_indx = get_speed_index();
|
||||
//
|
||||
//direction = get_direction();
|
||||
|
||||
|
||||
RFE_Pulled = !(gpio_get_level(CONFIG_RFE_GPIO));
|
||||
|
||||
duty = get_enc_in_counter();
|
||||
set_mcpwm_duty(duty);
|
||||
//Current_bridge = get_current_bridge(adc1_handle, CONFIG_I_SENSE_ADC);
|
||||
//gpio_set_level(CONFIG_LIN_U_GPIO,1);
|
||||
|
||||
|
||||
default:
|
||||
pwmStopAll();
|
||||
break;
|
||||
snprintf(display_message, sizeof(display_message), "PWM-Param.");
|
||||
ssd1306_display_text(dev_pt, 1, display_message, strlen(display_message), false);
|
||||
|
||||
snprintf(display_message, sizeof(display_message), "PWMFreq.: %ik ", (mcpwm_freq/1000));
|
||||
ssd1306_display_text(dev_pt, 3, display_message, 14, !(menu_counter));
|
||||
|
||||
snprintf(display_message, sizeof(display_message), "Duty: %.1f%% ", get_duty());
|
||||
ssd1306_display_text(dev_pt, 4, display_message, 14, !(menu_counter-1));
|
||||
|
||||
snprintf(display_message, sizeof(display_message), "DeadTime: %i ", CONFIG_DEAD_TIME_PWM);
|
||||
ssd1306_display_text(dev_pt, 5, display_message, 14, !(menu_counter-2));
|
||||
|
||||
if (RFE_Pulled){
|
||||
snprintf(display_message, sizeof(display_message), "RFE pulled ");
|
||||
}
|
||||
|
||||
}else{
|
||||
ssd1306_display_text(dev_pt, 1, "Bridge=OFF", 10, false);
|
||||
pwmStopAll();
|
||||
else{
|
||||
snprintf(display_message, sizeof(display_message), "RFE not pulled");
|
||||
}
|
||||
|
||||
ssd1306_display_text(dev_pt, 7, display_message, 14, !(menu_counter-3));
|
||||
|
||||
snprintf(display_message, sizeof(display_message), "Torque: %lu", Torque);
|
||||
ssd1306_display_text(dev_pt, 2, display_message, 11, false);
|
||||
|
||||
@@ -86,9 +120,9 @@ void app_main(void)
|
||||
|
||||
snprintf(display_message, sizeof(display_message), "W: %ldmA",Current_W);
|
||||
ssd1306_display_text(dev_pt, 7, display_message, strlen(display_message), false);
|
||||
//gpio_set_level(CONFIG_RFE_GPIO,0);
|
||||
|
||||
vTaskDelay(500 / portTICK_PERIOD_MS); // Verzögerung für die Task-Schleife
|
||||
i++;
|
||||
///gpio_set_level(CONFIG_RFE_GPIO,0);
|
||||
*/
|
||||
//vTaskDelay(100 / portTICK_PERIOD_MS); // Verzögerung für die Task-Schleife
|
||||
//i++;
|
||||
}
|
||||
}
|
||||
|
||||
346
main/functions.c
Normal file → Executable file
346
main/functions.c
Normal file → Executable file
@@ -1,155 +1,22 @@
|
||||
|
||||
#include "functions.h"
|
||||
adc_cali_handle_t cali_handle= NULL;
|
||||
void configure_GPIO_dir(const char *TAG)
|
||||
{
|
||||
/* reset every used GPIO-pin */
|
||||
gpio_reset_pin(CONFIG_HIN_U_GPIO);
|
||||
gpio_reset_pin(CONFIG_HIN_V_GPIO);
|
||||
gpio_reset_pin(CONFIG_HIN_W_GPIO);
|
||||
#include <string.h>
|
||||
#include "esp_log.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "parsed_pins.h"
|
||||
#include "sdkconfig.h"
|
||||
|
||||
gpio_reset_pin(CONFIG_LIN_U_GPIO);
|
||||
gpio_reset_pin(CONFIG_LIN_V_GPIO);
|
||||
gpio_reset_pin(CONFIG_LIN_W_GPIO);
|
||||
|
||||
gpio_reset_pin(CONFIG_HALL_A_GPIO);
|
||||
gpio_reset_pin(CONFIG_HALL_B_GPIO);
|
||||
gpio_reset_pin(CONFIG_HALL_C_GPIO);
|
||||
|
||||
//gpio_reset_pin(CONFIG_IN_ENC_A_GPIO);
|
||||
gpio_reset_pin(CONFIG_IN_ENC_B_GPIO);
|
||||
gpio_reset_pin(CONFIG_IN_ENC_BUT_GPIO);
|
||||
//gpio_reset_pin(CONFIG_BUTTON_GPIO);
|
||||
|
||||
|
||||
gpio_reset_pin(CONFIG_EXT_ENC_LEFT_GPIO);
|
||||
gpio_reset_pin(CONFIG_EXT_ENC_RIGHT_GPIO);
|
||||
gpio_reset_pin(CONFIG_RFE_GPIO);
|
||||
|
||||
/* Set the GPIO as a push/pull output */
|
||||
gpio_set_direction(CONFIG_HIN_U_GPIO, GPIO_MODE_OUTPUT);
|
||||
gpio_set_direction(CONFIG_HIN_V_GPIO, GPIO_MODE_OUTPUT);
|
||||
gpio_set_direction(CONFIG_HIN_W_GPIO, GPIO_MODE_OUTPUT);
|
||||
|
||||
gpio_set_direction(CONFIG_LIN_U_GPIO, GPIO_MODE_OUTPUT);
|
||||
gpio_set_direction(CONFIG_LIN_V_GPIO, GPIO_MODE_OUTPUT);
|
||||
gpio_set_direction(CONFIG_LIN_W_GPIO, GPIO_MODE_OUTPUT);
|
||||
|
||||
gpio_set_direction(CONFIG_HALL_A_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_HALL_B_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_HALL_C_GPIO, GPIO_MODE_INPUT);
|
||||
|
||||
//gpio_set_direction(CONFIG_IN_ENC_A_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_IN_ENC_B_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_IN_ENC_BUT_GPIO, GPIO_MODE_INPUT);
|
||||
//gpio_set_direction(CONFIG_BUTTON_GPIO, GPIO_MODE_INPUT);
|
||||
|
||||
|
||||
gpio_set_direction(CONFIG_EXT_ENC_LEFT_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_EXT_ENC_RIGHT_GPIO, GPIO_MODE_INPUT);
|
||||
gpio_set_direction(CONFIG_RFE_GPIO, GPIO_MODE_OUTPUT);
|
||||
ESP_LOGI(TAG, "GPIO dirs configured for DIY power PCB");
|
||||
}
|
||||
// Globale Variable für die Kalibrierung
|
||||
|
||||
adc_oneshot_unit_handle_t configure_ADC1()
|
||||
{
|
||||
adc_oneshot_unit_handle_t adc1_handle;
|
||||
|
||||
// ADC1 Initialisierung
|
||||
adc_oneshot_unit_init_cfg_t init_config = {
|
||||
.unit_id = ADC_UNIT_1,
|
||||
.ulp_mode = ADC_ULP_MODE_DISABLE,
|
||||
};
|
||||
ESP_ERROR_CHECK(adc_oneshot_new_unit(&init_config, &adc1_handle));
|
||||
|
||||
// Kanal-Konfiguration
|
||||
adc_oneshot_chan_cfg_t config = {
|
||||
.bitwidth = ADC_BITWIDTH_DEFAULT,
|
||||
.atten = ADC_ATTEN_DB_12,
|
||||
};
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_TORQUE_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_U_SENSE_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_I_SENSE_U_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_I_SENSE_V_ADC, &config));
|
||||
ESP_ERROR_CHECK(adc_oneshot_config_channel(adc1_handle, CONFIG_I_SENSE_W_ADC, &config));
|
||||
|
||||
// Kalibrierung initialisieren
|
||||
adc_cali_line_fitting_config_t cali_config = {
|
||||
.atten = ADC_ATTEN_DB_12,
|
||||
.bitwidth = ADC_BITWIDTH_DEFAULT,
|
||||
};
|
||||
|
||||
esp_err_t ret = adc_cali_create_scheme_line_fitting(&cali_config, &cali_handle);
|
||||
if (ret == ESP_OK) {
|
||||
ESP_LOGI("ADC", "ADC-Kalibrierung erfolgreich initialisiert");
|
||||
} else {
|
||||
ESP_LOGW("ADC", "ADC-Kalibrierung nicht möglich, Rohwerte werden verwendet");
|
||||
cali_handle = NULL; // Keine Kalibrierung verfügbar
|
||||
}
|
||||
|
||||
return adc1_handle;
|
||||
}
|
||||
|
||||
uint32_t read_voltage(adc_oneshot_unit_handle_t adc1_handle, int channel) {
|
||||
int adc_raw = 0;
|
||||
int voltage_calibrated = 0; // Verwende int für die Kalibrierungsfunktion
|
||||
uint32_t voltage = 0; // Konvertiere später zu uint32_t
|
||||
|
||||
// ADC-Rohwert lesen
|
||||
ESP_ERROR_CHECK(adc_oneshot_read(adc1_handle, channel, &adc_raw));
|
||||
|
||||
// Kalibrierung anwenden, falls verfügbar
|
||||
if (cali_handle) {
|
||||
ESP_ERROR_CHECK(adc_cali_raw_to_voltage(cali_handle, adc_raw, &voltage_calibrated));
|
||||
voltage = (uint32_t) voltage_calibrated; // Konvertiere zu uint32_t
|
||||
} else {
|
||||
voltage = adc_raw; // Fallback auf Rohwert
|
||||
}
|
||||
|
||||
return voltage;
|
||||
}
|
||||
// Funktion zur Umrechnung in spezifische Spannung
|
||||
uint32_t get_voltage_in(adc_oneshot_unit_handle_t adc1_handle)
|
||||
{
|
||||
uint32_t adc_voltage = read_voltage(adc1_handle, CONFIG_U_SENSE_ADC);
|
||||
ESP_LOGI("ADC", "ADC%d:voltage:%ld", CONFIG_U_SENSE_ADC, adc_voltage);
|
||||
// Beispielhafte Umrechnung; Wert an eigene Anwendung anpassen
|
||||
uint32_t voltage_in = adc_voltage / 0.0909;
|
||||
return voltage_in;
|
||||
}
|
||||
|
||||
int32_t get_current_ASC712(adc_oneshot_unit_handle_t adc1_handle, int ADC_pin)
|
||||
{
|
||||
int32_t adc_voltage = read_voltage(adc1_handle,ADC_pin);
|
||||
int32_t current = (adc_voltage -2500)*5.405;
|
||||
ESP_LOGI("ADC", "ADC%d:voltage:%ldcurrent%ld", ADC_pin, adc_voltage, current);
|
||||
return current;
|
||||
}
|
||||
|
||||
uint32_t get_torque(adc_oneshot_unit_handle_t adc1_handle)
|
||||
{
|
||||
uint32_t adc_voltage =read_voltage(adc1_handle,CONFIG_TORQUE_ADC);
|
||||
uint32_t torque = adc_voltage/33;
|
||||
|
||||
return torque;
|
||||
}
|
||||
int32_t get_current_bridge(adc_oneshot_unit_handle_t adc1_handle, int ADC_pin){
|
||||
int32_t adc_voltage = read_voltage(adc1_handle,ADC_pin);
|
||||
ESP_LOGI("CurrentBridge", "ADC:%ld",adc_voltage);
|
||||
int32_t current = ((adc_voltage- 142)/6.77)/0.007;
|
||||
return current;
|
||||
}
|
||||
|
||||
|
||||
SSD1306_t *configure_OLED(const char *TAG)
|
||||
/*############################################*/
|
||||
/*############## Display-Setup ###############*/
|
||||
/*############################################*/
|
||||
SSD1306_t *configure_OLED_old()
|
||||
{
|
||||
static SSD1306_t dev;
|
||||
//int center, top, bottom;
|
||||
//char lineChar[20];
|
||||
|
||||
i2c_master_init(&dev, CONFIG_SDA_GPIO, CONFIG_SCL_GPIO, CONFIG_RESET_GPIO);
|
||||
ESP_LOGI(TAG, "Panel is 128x64");
|
||||
ESP_LOGI("OLED", "Panel is 128x64");
|
||||
ssd1306_init(&dev, 128, 64);
|
||||
ssd1306_clear_screen(&dev, false);
|
||||
ssd1306_contrast(&dev, 0xff);
|
||||
@@ -159,146 +26,59 @@ SSD1306_t *configure_OLED(const char *TAG)
|
||||
return &dev;
|
||||
}
|
||||
|
||||
void set_PWM_Timer()
|
||||
{
|
||||
ledc_timer_config_t ledc_timer = {
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE,
|
||||
.timer_num = LEDC_TIMER_0,
|
||||
.duty_resolution = LEDC_TIMER_10_BIT,
|
||||
.freq_hz = CONFIG_FREQ_PWM_HIN,
|
||||
.clk_cfg = LEDC_AUTO_CLK
|
||||
};
|
||||
esp_err_t err = ledc_timer_config(&ledc_timer);
|
||||
if (err != ESP_OK) {
|
||||
printf("Fehler beim Konfigurieren des LEDC-Timers: %s\n", esp_err_to_name(err));
|
||||
return;
|
||||
|
||||
|
||||
/*############################################*/
|
||||
/*############ Blockkommutierung #############*/
|
||||
/*############################################*/
|
||||
bool get_Hall(int HallSensorGPIO){
|
||||
char* TAG="";
|
||||
|
||||
if(HallSensorGPIO == CONFIG_HALL_A_GPIO){
|
||||
TAG = "HALL_A";
|
||||
}else if(HallSensorGPIO == CONFIG_HALL_B_GPIO){
|
||||
TAG = "HALL_B";
|
||||
}
|
||||
|
||||
}
|
||||
void set_PWM()
|
||||
{
|
||||
ledc_channel_config_t ledc_channel_HIN_U =
|
||||
{
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE, // Gleicher Modus wie beim Timer
|
||||
.channel = LEDC_CHANNEL_0, // Kanal 0 verwenden
|
||||
.timer_sel = LEDC_TIMER_0, // Timer 0 zuweisen
|
||||
.intr_type = LEDC_INTR_DISABLE, // Keine Interrupts
|
||||
.gpio_num = CONFIG_HIN_U_GPIO,
|
||||
.duty = 0, //
|
||||
.hpoint = 0 // Start des PWM-Signals
|
||||
};
|
||||
ledc_channel_config(&ledc_channel_HIN_U); // Kanal konfigurieren
|
||||
ledc_channel_config_t ledc_channel_HIN_V =
|
||||
{
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE, // Gleicher Modus wie beim Timer
|
||||
.channel = LEDC_CHANNEL_1, // Kanal 0 verwenden
|
||||
.timer_sel = LEDC_TIMER_0, // Timer 0 zuweisen
|
||||
.intr_type = LEDC_INTR_DISABLE, // Keine Interrupts
|
||||
.gpio_num = CONFIG_HIN_V_GPIO,
|
||||
.duty = 0, //
|
||||
.hpoint = 0 // Start des PWM-Signals
|
||||
};
|
||||
ledc_channel_config(&ledc_channel_HIN_V); // Kanal konfigurieren
|
||||
ledc_channel_config_t ledc_channel_HIN_W =
|
||||
{
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE, // Gleicher Modus wie beim Timer
|
||||
.channel = LEDC_CHANNEL_2, // Kanal 0 verwenden
|
||||
.timer_sel = LEDC_TIMER_0, // Timer 0 zuweisen
|
||||
.intr_type = LEDC_INTR_DISABLE, // Keine Interrupts
|
||||
.gpio_num = CONFIG_HIN_W_GPIO,
|
||||
.duty = 0, //
|
||||
.hpoint = 0 // Start des PWM-Signals
|
||||
};
|
||||
ledc_channel_config(&ledc_channel_HIN_W); // Kanal konfigurieren
|
||||
}
|
||||
void pwmStart(int PWM_CH, int Duty){
|
||||
ledc_set_duty(LEDC_HIGH_SPEED_MODE,PWM_CH, Duty);
|
||||
ledc_update_duty(LEDC_HIGH_SPEED_MODE,PWM_CH);
|
||||
}
|
||||
|
||||
void pwmStop(int PWM_CH){
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, PWM_CH, 0);
|
||||
}
|
||||
void pwmStopAll(){
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, HIN_U_CH, 0);
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, HIN_V_CH, 0);
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, HIN_W_CH, 0);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 0);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 0);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 0);
|
||||
}
|
||||
|
||||
|
||||
void U_V_start(int duty)
|
||||
{
|
||||
//HIN_V und LIN_U abschalten
|
||||
pwmStop(HIN_V_CH);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_U_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 1);
|
||||
}
|
||||
void V_U_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_V abschalten
|
||||
pwmStop(HIN_U_CH);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 0);
|
||||
//HIN_V und LIN_U einschalten
|
||||
pwmStart(HIN_V_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 1);
|
||||
}
|
||||
void U_W_start(int duty)
|
||||
{
|
||||
//HIN_W und LIN_U abschalten
|
||||
pwmStop(HIN_W_CH);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_W_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 1);
|
||||
}
|
||||
void W_U_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_W abschalten
|
||||
pwmStop(HIN_U_CH);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_W_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 1);
|
||||
}
|
||||
void V_W_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_W abschalten
|
||||
pwmStop(HIN_W_CH);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_V_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 1);
|
||||
}
|
||||
|
||||
void W_V_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_W abschalten
|
||||
pwmStop(HIN_V_CH);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_W_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 1);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
//Ausgelagert in Preprocessing python program, generate_pins_header.py
|
||||
void parse_3pins(const char *TAG, const char *pin_string, int *pins) {
|
||||
int pin_count = 0; // Jetzt ein Integer, keine Null-Pointer-Dereferenzierung
|
||||
char *token;
|
||||
char *pin_list = strdup(pin_string); // Kopie der String-Option
|
||||
|
||||
token = strtok(pin_list, ",");
|
||||
while (token != NULL && pin_count < 3) { // maximal 3 Pins
|
||||
pins[pin_count] = atoi(token); // Umwandlung in Integer
|
||||
pin_count++;
|
||||
token = strtok(NULL, ",");
|
||||
else if(HallSensorGPIO == CONFIG_HALL_C_GPIO){
|
||||
TAG = "HALL_C";
|
||||
}else{
|
||||
TAG = "Undefinded";
|
||||
}
|
||||
|
||||
bool level = gpio_get_level(HallSensorGPIO);
|
||||
|
||||
if(level){
|
||||
ESP_LOGI(TAG, "HIGH");
|
||||
}else{
|
||||
ESP_LOGI(TAG,"LOW");
|
||||
}
|
||||
return level;
|
||||
}
|
||||
HallState get_Hall_Combi(){
|
||||
|
||||
int hall_A = gpio_get_level(CONFIG_HALL_A_GPIO);
|
||||
int hall_B = gpio_get_level(CONFIG_HALL_B_GPIO);
|
||||
int hall_C = gpio_get_level(CONFIG_HALL_C_GPIO);
|
||||
|
||||
// Wandelt die GPIO-Levels in einen binären Wert um
|
||||
return (HallState)((hall_A << 2) | (hall_B << 1) | hall_C);
|
||||
|
||||
}
|
||||
OutCombis get_output_combination(HallState hall_state) {
|
||||
switch (hall_state) {
|
||||
case HALL_001:
|
||||
return OUT_U_W;
|
||||
case HALL_010:
|
||||
return OUT_W_V;
|
||||
case HALL_011:
|
||||
return OUT_U_V;
|
||||
case HALL_100:
|
||||
return OUT_V_U;
|
||||
case HALL_101:
|
||||
return OUT_V_W;
|
||||
case HALL_110:
|
||||
return OUT_W_U;
|
||||
default:
|
||||
return COMBI_COUNT; // Ungültiger Zustand
|
||||
}
|
||||
free(pin_list); // Speicher freigeben
|
||||
}
|
||||
0
main/idf_component.yml
Normal file → Executable file
0
main/idf_component.yml
Normal file → Executable file
9
main/include/ADC.h
Executable file
9
main/include/ADC.h
Executable file
@@ -0,0 +1,9 @@
|
||||
#ifndef GPIO_H
|
||||
#define GPIO_H
|
||||
#include <stdint.h>
|
||||
void configure_ADC1();
|
||||
uint32_t get_voltage_in();
|
||||
uint32_t get_torque();
|
||||
int32_t get_current_ASC712(int ADC_pin);
|
||||
int32_t get_current_bridge(int ADC_pin);
|
||||
#endif
|
||||
19
main/include/GPIO.h
Executable file
19
main/include/GPIO.h
Executable file
@@ -0,0 +1,19 @@
|
||||
#ifndef GPIO2_H
|
||||
#define GPIO2_H
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
//configure GPIOs
|
||||
void configure_GPIO_dir();
|
||||
|
||||
//functions for external Encoder
|
||||
int get_direction();
|
||||
float get_speed_index();
|
||||
float get_speed_AB();
|
||||
|
||||
//functions for internal Encoder
|
||||
//int16_t get_enc_in_counter();
|
||||
//void set_enc_in_counter(int16_t inital_value);
|
||||
//bool get_enc_in_but();
|
||||
|
||||
#endif
|
||||
64
main/include/functions.h
Normal file → Executable file
64
main/include/functions.h
Normal file → Executable file
@@ -1,46 +1,24 @@
|
||||
// functions.h
|
||||
#include <stdio.h>
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "esp_log.h"
|
||||
#include "sdkconfig.h"
|
||||
#include "driver/ledc.h"
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include "parsed_pins.h"
|
||||
#include "esp_adc/adc_cali.h"
|
||||
#include "esp_adc/adc_cali_scheme.h"
|
||||
#ifndef FUNCTIONS_H
|
||||
#define FUNCTIONS_H
|
||||
|
||||
|
||||
#include "ssd1306.h"
|
||||
#include "esp_adc/adc_oneshot.h"
|
||||
#define HIN_U_CH 0
|
||||
#define HIN_V_CH 1
|
||||
#define HIN_W_CH 2
|
||||
#include <stdbool.h>
|
||||
#include "mcpwm.h"
|
||||
typedef enum {
|
||||
HALL_000 = 0b000, // Ungültiger Zustand
|
||||
HALL_001 = 0b001,
|
||||
HALL_010 = 0b010,
|
||||
HALL_011 = 0b011,
|
||||
HALL_100 = 0b100,
|
||||
HALL_101 = 0b101,
|
||||
HALL_110 = 0b110,
|
||||
HALL_111 = 0b111 // Ungültiger Zustand
|
||||
} HallState;
|
||||
|
||||
#ifndef MY_COMPONENT_H
|
||||
#define MY_COMPONENT_H
|
||||
extern adc_cali_handle_t cali_handle;
|
||||
|
||||
// Deklaration der Funktion, die in my_component.c implementiert ist
|
||||
void configure_GPIO_dir(const char *TAG);
|
||||
adc_oneshot_unit_handle_t configure_ADC1();
|
||||
uint32_t read_voltage(adc_oneshot_unit_handle_t adc1_handle, int channel);
|
||||
uint32_t get_voltage_in(adc_oneshot_unit_handle_t adc1_handle);
|
||||
uint32_t get_torque(adc_oneshot_unit_handle_t adc1_handle);
|
||||
int32_t get_current_ASC712(adc_oneshot_unit_handle_t adc1_handle, int ADC_pin);
|
||||
int32_t get_current_bridge(adc_oneshot_unit_handle_t adc1_handle, int ADC_pin);
|
||||
void set_PWM_Timer();
|
||||
void set_PWM();
|
||||
void pwmStart(int PWM_CH,int Duty);
|
||||
void pwmStop(int PWM_CH);
|
||||
void pwmStopAll();
|
||||
void U_V_start(int duty);
|
||||
void V_U_start(int duty);
|
||||
void U_W_start(int duty);
|
||||
void W_U_start(int duty);
|
||||
void V_W_start(int duty);
|
||||
void W_V_start(int duty);
|
||||
void parse_3pins(const char *TAG, const char *pin_string, int *pins);
|
||||
SSD1306_t *configure_OLED(const char *TAG);
|
||||
|
||||
#endif // MY_COMPONENT_H
|
||||
bool get_Hall(int HallSensorGPIO);
|
||||
SSD1306_t *configure_OLED_old();
|
||||
HallState get_Hall_Combi();
|
||||
OutCombis get_output_combination(HallState hall_state);
|
||||
#endif
|
||||
34
main/include/mcpwm.h
Executable file
34
main/include/mcpwm.h
Executable file
@@ -0,0 +1,34 @@
|
||||
#ifndef MCPWM_H
|
||||
#define MCPWM_H
|
||||
#include "hal/mcpwm_types.h"
|
||||
#include "driver/mcpwm_prelude.h"
|
||||
typedef enum {
|
||||
PHASE_U,
|
||||
PHASE_V,
|
||||
PHASE_W
|
||||
} Phase;
|
||||
|
||||
typedef enum {
|
||||
OUT_U_V,
|
||||
OUT_U_W,
|
||||
OUT_V_W,
|
||||
OUT_V_U,
|
||||
OUT_W_U,
|
||||
OUT_W_V,
|
||||
OUT_U,
|
||||
OUT_V,
|
||||
OUT_W,
|
||||
OUT_UVW,
|
||||
COMBI_COUNT
|
||||
}OutCombis;
|
||||
|
||||
void mcpwm_init();
|
||||
void stop_mcpwm_output();
|
||||
void configure_mcpwm_output(OutCombis out_combi);
|
||||
esp_err_t start_mcpwm_output();
|
||||
esp_err_t set_mcpwm_duty(float duty);
|
||||
esp_err_t set_mcpwm_frequency(uint32_t frequency);
|
||||
void get_comps(mcpwm_cmpr_handle_t comps[3]);
|
||||
float get_duty();
|
||||
uint32_t get_frequency();
|
||||
#endif
|
||||
13
main/include/menu.h
Normal file
13
main/include/menu.h
Normal file
@@ -0,0 +1,13 @@
|
||||
//Zum Erstellen der gesamten Benutzeroberfläche. Samt einlesen des Inkrementalgebers, und Übergabe von Parametern an "Backend"
|
||||
#ifndef MENU_H
|
||||
#define MENU_H
|
||||
|
||||
|
||||
|
||||
extern const char *OutCombi_names[];
|
||||
|
||||
void configure_OLED();
|
||||
void config_internal_Encoder();
|
||||
void menu_loop();
|
||||
|
||||
#endif
|
||||
404
main/mcpwm.c
Executable file
404
main/mcpwm.c
Executable file
@@ -0,0 +1,404 @@
|
||||
#include "mcpwm.h"
|
||||
#include "esp_timer.h"
|
||||
#include "esp_log.h"
|
||||
#include "math.h"
|
||||
#include "parsed_pins.h"
|
||||
#include "sdkconfig.h"
|
||||
|
||||
//create Timers
|
||||
static mcpwm_timer_handle_t timer_U = NULL;
|
||||
static mcpwm_timer_handle_t timer_V = NULL;
|
||||
static mcpwm_timer_handle_t timer_W = NULL;
|
||||
//create Operators
|
||||
static mcpwm_oper_handle_t operator_U = NULL;
|
||||
static mcpwm_oper_handle_t operator_V = NULL;
|
||||
static mcpwm_oper_handle_t operator_W = NULL;
|
||||
//create PWM-Signals
|
||||
static mcpwm_cmpr_handle_t comperator_U = NULL;
|
||||
static mcpwm_cmpr_handle_t comperator_V = NULL;
|
||||
static mcpwm_cmpr_handle_t comperator_W = NULL;
|
||||
//create generators for every pin
|
||||
static mcpwm_gen_handle_t generator_U_HIN = NULL;
|
||||
static mcpwm_gen_handle_t generator_V_HIN = NULL;
|
||||
static mcpwm_gen_handle_t generator_W_HIN = NULL;
|
||||
static mcpwm_gen_handle_t generator_U_LIN = NULL;
|
||||
static mcpwm_gen_handle_t generator_V_LIN = NULL;
|
||||
static mcpwm_gen_handle_t generator_W_LIN = NULL;
|
||||
|
||||
typedef enum {
|
||||
Highside,
|
||||
Lowside,
|
||||
OFF
|
||||
} Phase_state;
|
||||
|
||||
typedef struct {
|
||||
Phase phase;
|
||||
Phase_state state;
|
||||
} PhaseConfiguration;
|
||||
PhaseConfiguration phase_configurations[3] = {
|
||||
{ PHASE_U, Highside },
|
||||
{ PHASE_V, Lowside },
|
||||
{ PHASE_W, OFF }
|
||||
};
|
||||
uint32_t mcpwm_frequency = CONFIG_FREQ_PWM;
|
||||
uint32_t periode_ticks = CONFIG_TIMER_BASE_FREQ/CONFIG_FREQ_PWM;
|
||||
float duty = CONFIG_DUTY_PWM;
|
||||
|
||||
/*############################################*/
|
||||
/*############### MCPWM-Setup ################*/
|
||||
/*############################################*/
|
||||
|
||||
static void conf_gens(){
|
||||
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_U_HIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comperator_U, MCPWM_GEN_ACTION_LOW)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_U_HIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, comperator_U, MCPWM_GEN_ACTION_HIGH)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_U_LIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comperator_U, MCPWM_GEN_ACTION_LOW)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_U_LIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, comperator_U, MCPWM_GEN_ACTION_HIGH)));
|
||||
|
||||
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_V_HIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comperator_V, MCPWM_GEN_ACTION_LOW)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_V_HIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, comperator_V, MCPWM_GEN_ACTION_HIGH)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_V_LIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comperator_V, MCPWM_GEN_ACTION_LOW)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_V_LIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, comperator_V, MCPWM_GEN_ACTION_HIGH)));
|
||||
|
||||
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_W_HIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comperator_W, MCPWM_GEN_ACTION_LOW)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_W_HIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, comperator_W, MCPWM_GEN_ACTION_HIGH)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_W_LIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, comperator_W, MCPWM_GEN_ACTION_LOW)));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(generator_W_LIN, MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, comperator_W, MCPWM_GEN_ACTION_HIGH)));
|
||||
|
||||
|
||||
}
|
||||
esp_err_t set_mcpwm_duty(float new_duty){
|
||||
if (timer_U == NULL) {
|
||||
return ESP_ERR_INVALID_STATE; // Fehlerbehandlung, wenn mcpwm nicht initialisiert wurde
|
||||
}
|
||||
duty = new_duty;
|
||||
ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comperator_U, (periode_ticks*duty/100)/2));
|
||||
ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comperator_V, (periode_ticks*duty/100)/2));
|
||||
ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(comperator_W, (periode_ticks*duty/100)/2));
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
void stop_mcpwm_output(){
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_LIN, 1,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_LIN, 1,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_LIN, 1,true));
|
||||
}
|
||||
void mcpwm_init(){
|
||||
ESP_LOGI("MCPWM","started");
|
||||
double tick_period_ns = 1e9 / CONFIG_TIMER_BASE_FREQ; // Zeit pro Tick in ns
|
||||
uint32_t dead_time_ticks = (uint32_t)round(CONFIG_DEAD_TIME_PWM / tick_period_ns);
|
||||
|
||||
//creating timer configs and linking them with the timers
|
||||
mcpwm_timer_config_t timer_config =
|
||||
{
|
||||
.group_id = 0,
|
||||
.clk_src = MCPWM_TIMER_CLK_SRC_DEFAULT,
|
||||
.resolution_hz = CONFIG_TIMER_BASE_FREQ, //40MHz
|
||||
.period_ticks = periode_ticks, //40MHz/2KHz = 20KHz
|
||||
.count_mode = MCPWM_TIMER_COUNT_MODE_UP_DOWN,
|
||||
.flags ={
|
||||
.update_period_on_empty = 1,
|
||||
}
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_timer(&timer_config, &timer_U));
|
||||
ESP_ERROR_CHECK(mcpwm_new_timer(&timer_config, &timer_V));
|
||||
ESP_ERROR_CHECK(mcpwm_new_timer(&timer_config, &timer_W));
|
||||
|
||||
ESP_ERROR_CHECK(mcpwm_timer_enable(timer_U));
|
||||
ESP_ERROR_CHECK(mcpwm_timer_start_stop(timer_U,MCPWM_TIMER_START_NO_STOP));
|
||||
ESP_ERROR_CHECK(mcpwm_timer_enable(timer_V));
|
||||
ESP_ERROR_CHECK(mcpwm_timer_start_stop(timer_V,MCPWM_TIMER_START_NO_STOP));
|
||||
ESP_ERROR_CHECK(mcpwm_timer_enable(timer_W));
|
||||
ESP_ERROR_CHECK(mcpwm_timer_start_stop(timer_W,MCPWM_TIMER_START_NO_STOP));
|
||||
|
||||
|
||||
//set Timer_U as an sync_signal
|
||||
mcpwm_sync_handle_t sync_signal = NULL;
|
||||
mcpwm_timer_sync_src_config_t sync_src_config =
|
||||
{
|
||||
.flags.propagate_input_sync = SOC_FLASH_ENCRYPTED_XTS_AES_BLOCK_MAX,
|
||||
.timer_event = MCPWM_TIMER_EVENT_EMPTY,
|
||||
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_timer_sync_src(timer_U,&sync_src_config, &sync_signal));
|
||||
//set Timer_V as an Slave of Timer_U with another phase
|
||||
mcpwm_timer_sync_phase_config_t sync_phase_V_config =
|
||||
{
|
||||
.sync_src = sync_signal,
|
||||
.count_value = periode_ticks/6, //120 degree delayed
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_timer_set_phase_on_sync(timer_V,&sync_phase_V_config));
|
||||
//set Timer_W as an Slave of Timer_U with another phase
|
||||
mcpwm_timer_sync_phase_config_t sync_phase_W_config =
|
||||
{
|
||||
.sync_src = sync_signal,
|
||||
.count_value = periode_ticks*2/6, //240 degree delayed
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_timer_set_phase_on_sync(timer_W,&sync_phase_W_config));
|
||||
|
||||
|
||||
|
||||
//Operator for Timer_U
|
||||
mcpwm_operator_config_t operator_config =
|
||||
{
|
||||
.group_id=0,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config,&operator_U));
|
||||
ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config,&operator_V));
|
||||
ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config,&operator_W));
|
||||
|
||||
//connect PWM-Signals with Timers
|
||||
ESP_ERROR_CHECK(mcpwm_operator_connect_timer(operator_U, timer_U));
|
||||
ESP_ERROR_CHECK(mcpwm_operator_connect_timer(operator_V, timer_V));
|
||||
ESP_ERROR_CHECK(mcpwm_operator_connect_timer(operator_W, timer_W));
|
||||
|
||||
|
||||
|
||||
mcpwm_comparator_config_t comparator_config = {
|
||||
.flags.update_cmp_on_tez = true,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_comparator(operator_U, &comparator_config,&comperator_U));
|
||||
ESP_ERROR_CHECK(mcpwm_new_comparator(operator_V, &comparator_config,&comperator_V));
|
||||
ESP_ERROR_CHECK(mcpwm_new_comparator(operator_W, &comparator_config,&comperator_W));
|
||||
|
||||
|
||||
mcpwm_gen_handle_t *mcpwm_gens[] ={&generator_U_HIN,&generator_U_LIN,&generator_V_HIN,&generator_V_LIN,&generator_W_HIN,&generator_W_LIN};
|
||||
//HIN Pins
|
||||
//HIN_U
|
||||
mcpwm_generator_config_t generator_U_HIN_config ={
|
||||
.gen_gpio_num = CONFIG_HIN_U_GPIO,
|
||||
.flags.pull_down = 1,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_generator(operator_U, &generator_U_HIN_config, &generator_U_HIN));
|
||||
|
||||
//HIN_V
|
||||
mcpwm_generator_config_t generator_V_HIN_config ={
|
||||
.gen_gpio_num = CONFIG_HIN_V_GPIO,
|
||||
.flags.pull_down = 1,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_generator(operator_V, &generator_V_HIN_config, &generator_V_HIN));
|
||||
|
||||
//HIN_W
|
||||
mcpwm_generator_config_t generator_W_HIN_config ={
|
||||
.gen_gpio_num = CONFIG_HIN_W_GPIO,
|
||||
.flags.pull_down = 1,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_generator(operator_W, &generator_W_HIN_config, &generator_W_HIN));
|
||||
|
||||
//LIN_U
|
||||
mcpwm_generator_config_t generator_U_LIN_config ={
|
||||
.gen_gpio_num = CONFIG_LIN_U_GPIO,
|
||||
.flags.invert_pwm = 1,
|
||||
.flags.pull_down = 1,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_generator(operator_U, &generator_U_LIN_config, &generator_U_LIN));
|
||||
|
||||
//LIN_V
|
||||
mcpwm_generator_config_t generator_V_LIN_config ={
|
||||
.gen_gpio_num = CONFIG_LIN_V_GPIO,
|
||||
.flags.invert_pwm = 1,
|
||||
.flags.pull_down = 1,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_generator(operator_V, &generator_V_LIN_config, &generator_V_LIN));
|
||||
|
||||
//LIN_W
|
||||
mcpwm_generator_config_t generator_W_LIN_config ={
|
||||
.gen_gpio_num = CONFIG_LIN_W_GPIO,
|
||||
.flags.invert_pwm = 1,
|
||||
.flags.pull_down = 1,
|
||||
};
|
||||
ESP_ERROR_CHECK(mcpwm_new_generator(operator_W, &generator_W_LIN_config, &generator_W_LIN));
|
||||
|
||||
//set Dead times
|
||||
mcpwm_dead_time_config_t deadtime_config = {
|
||||
.posedge_delay_ticks = dead_time_ticks,
|
||||
.negedge_delay_ticks = 0,
|
||||
};
|
||||
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_dead_time(generator_U_HIN, generator_U_HIN,&deadtime_config));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_dead_time(generator_V_HIN, generator_V_HIN,&deadtime_config));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_dead_time(generator_W_HIN, generator_W_HIN,&deadtime_config));
|
||||
deadtime_config.posedge_delay_ticks = 0;
|
||||
deadtime_config.negedge_delay_ticks = dead_time_ticks;
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_dead_time(generator_U_HIN, generator_U_LIN, &deadtime_config));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_dead_time(generator_V_HIN, generator_V_LIN, &deadtime_config));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_dead_time(generator_W_HIN, generator_W_LIN, &deadtime_config));
|
||||
|
||||
conf_gens();
|
||||
stop_mcpwm_output();
|
||||
set_mcpwm_duty(duty);
|
||||
}
|
||||
|
||||
static void set_lowside(Phase lowside){
|
||||
switch (lowside){
|
||||
case PHASE_U:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_LIN, 0,true));
|
||||
break;
|
||||
case PHASE_V:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_LIN, 0,true));
|
||||
break;
|
||||
case PHASE_W:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_LIN, 0,true));
|
||||
break;
|
||||
|
||||
default:
|
||||
printf("Invalid phase selection\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
static void set_highside(Phase highside){
|
||||
switch (highside){
|
||||
|
||||
case PHASE_U:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_HIN, -1,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_LIN, -1,true));
|
||||
break;
|
||||
case PHASE_V:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_HIN, -1,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_LIN, -1,true));
|
||||
break;
|
||||
case PHASE_W:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_HIN, -1,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_LIN, -1,true));
|
||||
break;
|
||||
|
||||
default:
|
||||
printf("Invalid phase selection\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
static void set_inactive(Phase inactive){
|
||||
switch (inactive){
|
||||
case PHASE_U:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_U_LIN, 1,true));
|
||||
break;
|
||||
case PHASE_V:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_V_LIN, 1,true));
|
||||
break;
|
||||
case PHASE_W:
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_HIN, 0,true));
|
||||
ESP_ERROR_CHECK(mcpwm_generator_set_force_level(generator_W_LIN, 1,true));
|
||||
break;
|
||||
|
||||
default:
|
||||
printf("Invalid phase selection\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
esp_err_t start_mcpwm_output(){
|
||||
if (timer_U == NULL) {
|
||||
return ESP_ERR_INVALID_STATE; // Fehlerbehandlung, wenn mcpwm nicht initialisiert wurde
|
||||
}
|
||||
for (int i = 0; i < 3; i++) {
|
||||
switch (phase_configurations[i].state) {
|
||||
case Highside:
|
||||
set_highside(phase_configurations[i].phase);
|
||||
break;
|
||||
case Lowside:
|
||||
set_lowside(phase_configurations[i].phase);
|
||||
break;
|
||||
case OFF:
|
||||
set_inactive(phase_configurations[i].phase);
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
return ESP_OK;
|
||||
}
|
||||
void configure_mcpwm_output(OutCombis out_combi) {
|
||||
switch (out_combi) {
|
||||
case OUT_U_V:
|
||||
phase_configurations[0].state = Highside;
|
||||
phase_configurations[1].state = Lowside;
|
||||
phase_configurations[2].state = OFF;
|
||||
break;
|
||||
case OUT_U_W:
|
||||
phase_configurations[0].state = Highside;
|
||||
phase_configurations[1].state = OFF;
|
||||
phase_configurations[2].state = Lowside;
|
||||
break;
|
||||
case OUT_V_W:
|
||||
phase_configurations[0].state = OFF;
|
||||
phase_configurations[1].state = Highside;
|
||||
phase_configurations[2].state = Lowside;
|
||||
break;
|
||||
case OUT_V_U:
|
||||
phase_configurations[0].state = Lowside;
|
||||
phase_configurations[1].state = Highside;
|
||||
phase_configurations[2].state = OFF;
|
||||
break;
|
||||
case OUT_W_U:
|
||||
phase_configurations[0].state = Lowside;
|
||||
phase_configurations[1].state = OFF;
|
||||
phase_configurations[2].state = Highside;
|
||||
break;
|
||||
case OUT_W_V:
|
||||
phase_configurations[0].state = OFF;
|
||||
phase_configurations[1].state = Lowside;
|
||||
phase_configurations[2].state = Highside;
|
||||
break;
|
||||
case OUT_U:
|
||||
phase_configurations[0].state = Highside;
|
||||
phase_configurations[1].state = OFF;
|
||||
phase_configurations[2].state = OFF;
|
||||
break;
|
||||
case OUT_V:
|
||||
phase_configurations[0].state = OFF;
|
||||
phase_configurations[1].state = Highside;
|
||||
phase_configurations[2].state = OFF;
|
||||
break;
|
||||
case OUT_W:
|
||||
phase_configurations[0].state = OFF;
|
||||
phase_configurations[1].state = OFF;
|
||||
phase_configurations[2].state = Highside;
|
||||
break;
|
||||
case OUT_UVW:
|
||||
phase_configurations[0].state = Highside;
|
||||
phase_configurations[1].state = Highside;
|
||||
phase_configurations[2].state = Highside;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
esp_err_t set_mcpwm_frequency(uint32_t frequency_new){
|
||||
|
||||
if (timer_U == NULL) {
|
||||
return ESP_ERR_INVALID_STATE; // Fehlerbehandlung, wenn mcpwm nicht initialisiert wurde
|
||||
}
|
||||
periode_ticks = CONFIG_TIMER_BASE_FREQ/frequency_new;
|
||||
mcpwm_frequency = frequency_new;
|
||||
// Neue Konfiguration anwenden
|
||||
ESP_ERROR_CHECK(mcpwm_timer_set_period(timer_U, periode_ticks));
|
||||
ESP_ERROR_CHECK(mcpwm_timer_set_period(timer_V, periode_ticks));
|
||||
ESP_ERROR_CHECK(mcpwm_timer_set_period(timer_W, periode_ticks));
|
||||
|
||||
// dutycycle an neue Frequenz anpassen
|
||||
set_mcpwm_duty(duty);
|
||||
|
||||
return ESP_OK;
|
||||
}
|
||||
|
||||
void get_comps(mcpwm_cmpr_handle_t comps[3]) {
|
||||
comps[0] = comperator_U;
|
||||
comps[1] = comperator_V;
|
||||
comps[2] = comperator_W;
|
||||
}
|
||||
float get_duty() {
|
||||
return duty;
|
||||
}
|
||||
uint32_t get_frequency(){
|
||||
return mcpwm_frequency;
|
||||
}
|
||||
406
main/menu.c
Normal file
406
main/menu.c
Normal file
@@ -0,0 +1,406 @@
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include "esp_log.h"
|
||||
#include "ssd1306.h"
|
||||
#include "sdkconfig.h"
|
||||
#include "parsed_pins.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "GPIO.h"
|
||||
#include "menu.h"
|
||||
#include "esp_timer.h"
|
||||
#include "mcpwm.h"
|
||||
#include "ADC.h"
|
||||
#include "functions.h"
|
||||
|
||||
|
||||
|
||||
/*############################################*/
|
||||
/*############## Display-Setup ###############*/
|
||||
/*############################################*/
|
||||
static SSD1306_t dev;
|
||||
void configure_OLED()
|
||||
{
|
||||
i2c_master_init(&dev, CONFIG_SDA_GPIO, CONFIG_SCL_GPIO, -1);
|
||||
ESP_LOGI("OLED", "Panel is 128x64");
|
||||
ssd1306_init(&dev, 128, 64);
|
||||
ssd1306_clear_screen(&dev, false);
|
||||
ssd1306_contrast(&dev, 0xff);
|
||||
ssd1306_display_text_x3(&dev, 0, "Power", 5, false);
|
||||
ssd1306_display_text_x3(&dev, 4, " PCB", 4, false);
|
||||
|
||||
vTaskDelay(2000 / portTICK_PERIOD_MS);
|
||||
ssd1306_clear_screen(&dev, false);
|
||||
}
|
||||
|
||||
/*############################################*/
|
||||
/*############ Internal Encoder ##############*/
|
||||
/*############################################*/
|
||||
//Variablen
|
||||
static volatile int enc_in_counter = 0;
|
||||
static volatile int64_t last_interrupt_time = 0;
|
||||
static volatile uint16_t last_interrupt_time_but = 0;
|
||||
static volatile bool enc_in_button_flag = false;
|
||||
static volatile uint8_t last_state = 0;
|
||||
|
||||
static void IRAM_ATTR enc_in_isr_handler(void *arg) {
|
||||
static uint64_t last_interrupt_time = 0;
|
||||
|
||||
// Aktueller Zustand der Pins lesen
|
||||
uint8_t current_state = (gpio_get_level(CONFIG_IN_ENC_A_GPIO) << 1) | gpio_get_level(CONFIG_IN_ENC_B_GPIO);
|
||||
uint64_t interrupt_time = esp_timer_get_time();
|
||||
|
||||
// Zustandswechsel-Logik (FSM) ohne starre Entprellzeit
|
||||
if (current_state != last_state) {
|
||||
// Nur wenn der Wechsel signifikant verzögert ist (gute Flanke)
|
||||
if ((interrupt_time - last_interrupt_time) > CONFIG_IN_ENCODER_DEBOUNCE_TIME) {
|
||||
if ((last_state == 0b01 && current_state == 0b11) ||
|
||||
(last_state == 0b10 && current_state == 0b00)) {
|
||||
enc_in_counter++; // Vorwärtsdrehen
|
||||
} else if ((last_state == 0b10 && current_state == 0b11) ||
|
||||
(last_state == 0b01 && current_state == 0b00)) {
|
||||
enc_in_counter--; // Rückwärtsdrehen
|
||||
}
|
||||
last_state = current_state; // Zustand aktualisieren
|
||||
last_interrupt_time = interrupt_time;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static void IRAM_ATTR enc_in_but_isr_handler(void *arg) {
|
||||
uint64_t interrupt_time = esp_timer_get_time();
|
||||
|
||||
// Entprellung: Verhindert die Erfassung von Störungen aufgrund von Prellung
|
||||
if (interrupt_time - last_interrupt_time_but > (CONFIG_IN_ENCODER_DEBOUNCE_TIME*1000)) { // Entprellungszeit
|
||||
last_interrupt_time_but = interrupt_time; // Entprellzeit zurücksetzen
|
||||
if (gpio_get_level(CONFIG_IN_ENC_BUT_GPIO)) {
|
||||
enc_in_button_flag = true;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void config_internal_Encoder(){
|
||||
ESP_ERROR_CHECK(gpio_isr_handler_add(CONFIG_IN_ENC_A_GPIO, enc_in_isr_handler, NULL));
|
||||
ESP_ERROR_CHECK(gpio_isr_handler_add(CONFIG_IN_ENC_B_GPIO, enc_in_isr_handler, NULL));
|
||||
ESP_ERROR_CHECK(gpio_isr_handler_add(CONFIG_IN_ENC_BUT_GPIO, enc_in_but_isr_handler, NULL));
|
||||
}
|
||||
/*############################################*/
|
||||
/*############### Menu-Setup #################*/
|
||||
/*############################################*/
|
||||
typedef enum {
|
||||
MAIN_MENU,
|
||||
CONFIGURE_MENU,
|
||||
MORE_INFO_MENU
|
||||
} MenuState;
|
||||
|
||||
typedef enum {
|
||||
MCPWM_MODE,
|
||||
BLDC_MODE,
|
||||
DC_BRUSHED_MODE,
|
||||
MODE_COUNT
|
||||
}OperationMode;
|
||||
|
||||
const char *mode_names[] = {
|
||||
"MCPWM ",
|
||||
"BLDC ",
|
||||
"DC Brush"
|
||||
};
|
||||
|
||||
const char *OutCombi_names[]= {
|
||||
"+U -V ",
|
||||
"+U -W ",
|
||||
"+V -W ",
|
||||
"+V -U ",
|
||||
"+W -U ",
|
||||
"+W -V ",
|
||||
" +U ",
|
||||
" +V ",
|
||||
" +W ",
|
||||
"+U+V+W",
|
||||
"ERROR "
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
STATE_ACTIVE,
|
||||
STATE_DEAKTIVE,
|
||||
STATE_UV,
|
||||
STATE_OC
|
||||
} BridgeState;
|
||||
|
||||
const char *state_names[] = {
|
||||
"Active ",
|
||||
"Deaktive ",
|
||||
"UV ",
|
||||
"RFE (OC) "
|
||||
};
|
||||
|
||||
|
||||
//Globalevariablen
|
||||
volatile MenuState current_menu = MAIN_MENU;
|
||||
volatile OperationMode current_mode = MCPWM_MODE;
|
||||
volatile BridgeState current_bridge_state = STATE_DEAKTIVE;
|
||||
volatile OutCombis current_out_combi = OUT_U_V;
|
||||
|
||||
volatile bool ShouldState = false; //false==deaktive
|
||||
int cursor_position = 0;
|
||||
int max_cursor_pos = 0;
|
||||
bool in_editing = false;
|
||||
char display_message[100]; // Puffer für die Nachricht
|
||||
bool flag;
|
||||
uint16_t PWM_Frequency = 0;
|
||||
static void check_button_pressed(){
|
||||
if (enc_in_button_flag){
|
||||
enc_in_button_flag=false;
|
||||
|
||||
switch (current_menu){
|
||||
|
||||
case MAIN_MENU:
|
||||
switch(cursor_position){
|
||||
case 0:
|
||||
current_mode = (current_mode+1)% MODE_COUNT;
|
||||
break;
|
||||
case 1:
|
||||
ShouldState = !ShouldState;
|
||||
if(ShouldState){
|
||||
start_mcpwm_output();
|
||||
}else{
|
||||
stop_mcpwm_output();
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
current_menu = CONFIGURE_MENU;
|
||||
enc_in_counter=0;
|
||||
break;
|
||||
case 3:
|
||||
current_menu = MORE_INFO_MENU;
|
||||
enc_in_counter=0;
|
||||
break;
|
||||
case 4:
|
||||
if (current_mode==DC_BRUSHED_MODE){
|
||||
current_out_combi =(current_out_combi+1)%10;
|
||||
}else{
|
||||
current_out_combi =(current_out_combi+1)%6;
|
||||
}
|
||||
stop_mcpwm_output();
|
||||
configure_mcpwm_output(current_out_combi);
|
||||
ShouldState = false;
|
||||
break;
|
||||
default:
|
||||
snprintf(display_message, sizeof(display_message), "ERROR");
|
||||
ssd1306_display_text(&dev, 7, display_message, strlen(display_message), false);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case CONFIGURE_MENU:
|
||||
switch(cursor_position){
|
||||
case 0:
|
||||
if(in_editing){
|
||||
set_mcpwm_frequency(enc_in_counter*1000);
|
||||
in_editing = false;
|
||||
enc_in_counter= cursor_position;
|
||||
}else{
|
||||
in_editing = true;
|
||||
enc_in_counter = get_frequency()/1000;
|
||||
}
|
||||
|
||||
break;
|
||||
case 1:
|
||||
if(in_editing){
|
||||
set_mcpwm_duty((float)enc_in_counter);
|
||||
in_editing = false;
|
||||
enc_in_counter = cursor_position;
|
||||
}else{
|
||||
in_editing = true;
|
||||
enc_in_counter = (int)get_duty();
|
||||
}
|
||||
break;
|
||||
case 3:
|
||||
current_menu = MAIN_MENU;
|
||||
enc_in_counter=0;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case MORE_INFO_MENU:
|
||||
current_menu = MAIN_MENU;
|
||||
enc_in_counter=0;
|
||||
break;
|
||||
default:
|
||||
ESP_LOGE("Error","Not yet programmed");
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
static void getset_bridge_state(){
|
||||
|
||||
bool RFE_Pulled = !(gpio_get_level(CONFIG_RFE_GPIO));
|
||||
if(get_voltage_in()<18000){
|
||||
current_bridge_state=STATE_UV;
|
||||
}else if (RFE_Pulled){
|
||||
current_bridge_state=STATE_OC;
|
||||
}else if(!ShouldState){
|
||||
current_bridge_state=STATE_DEAKTIVE;
|
||||
}else{
|
||||
current_bridge_state=STATE_ACTIVE;
|
||||
}
|
||||
}
|
||||
|
||||
static void render_main_menu(){
|
||||
if(current_mode == BLDC_MODE)max_cursor_pos = 3;else max_cursor_pos=4;
|
||||
|
||||
//Mode
|
||||
snprintf(display_message, sizeof(display_message), "Mode: %s", mode_names[current_mode]);
|
||||
ssd1306_display_text(&dev, 1, display_message, strlen(display_message), cursor_position == 0);
|
||||
|
||||
//ShouldState Started oder Stopped
|
||||
snprintf(display_message, sizeof(display_message), "%s", ShouldState ? "Started" : "Stopped");
|
||||
ssd1306_display_text(&dev, 2, display_message, strlen(display_message), cursor_position == 1);
|
||||
|
||||
//Configure_Menu
|
||||
snprintf(display_message, sizeof(display_message), "Configure ->");
|
||||
ssd1306_display_text(&dev, 3, display_message, strlen(display_message), cursor_position == 2);
|
||||
|
||||
//More_Info_Menu
|
||||
snprintf(display_message, sizeof(display_message), "Sensor Info ->");
|
||||
ssd1306_display_text(&dev, 4, display_message, strlen(display_message),cursor_position == 3);
|
||||
|
||||
//Output Selection
|
||||
snprintf(display_message, sizeof(display_message), "Out: %s",OutCombi_names[current_out_combi]);
|
||||
ssd1306_display_text(&dev, 5, display_message, strlen(display_message), (current_mode == BLDC_MODE)|(cursor_position == 4));
|
||||
|
||||
|
||||
//State
|
||||
getset_bridge_state();
|
||||
snprintf(display_message, sizeof(display_message), "State: %s",state_names[current_bridge_state]);
|
||||
ssd1306_display_text(&dev, 6, display_message, strlen(display_message), true);
|
||||
|
||||
/*snprintf(display_message, sizeof(display_message), "cursor: %i %s",cursor_position,enc_in_button_flag ?"in" : "out");
|
||||
ssd1306_display_text(&dev, 7, display_message, strlen(display_message), true);
|
||||
*/}
|
||||
|
||||
static void render_config_menu(){
|
||||
max_cursor_pos = 3;
|
||||
|
||||
switch(current_mode){
|
||||
case MCPWM_MODE:
|
||||
case BLDC_MODE:
|
||||
//Titel
|
||||
snprintf(display_message, sizeof(display_message), "Conf. MCPWM");
|
||||
ssd1306_display_text(&dev, 1, display_message, strlen(display_message), false);
|
||||
|
||||
//Frequenz
|
||||
if(in_editing && cursor_position == 0){
|
||||
snprintf(display_message, sizeof(display_message), "PWMFreq.:%ikHz", enc_in_counter);
|
||||
ssd1306_display_text(&dev, 2, display_message, strlen(display_message), true);
|
||||
set_mcpwm_frequency(enc_in_counter*1000);
|
||||
}else{
|
||||
snprintf(display_message, sizeof(display_message), "PWMFreq.:%lukHz", (get_frequency()/1000));
|
||||
ssd1306_display_text(&dev, 2, display_message, strlen(display_message), cursor_position == 0);
|
||||
|
||||
}
|
||||
//Duty cycle
|
||||
if(in_editing && cursor_position == 1){
|
||||
snprintf(display_message, sizeof(display_message), "Duty: %.1f%%", (float)enc_in_counter);
|
||||
ssd1306_display_text(&dev, 3, display_message, strlen(display_message), cursor_position == 1);
|
||||
set_mcpwm_duty((float)enc_in_counter);
|
||||
}else{
|
||||
snprintf(display_message, sizeof(display_message), "Duty: %.1f%%", get_duty());
|
||||
ssd1306_display_text(&dev, 3, display_message, strlen(display_message), cursor_position == 1);
|
||||
}
|
||||
//Todzeit
|
||||
snprintf(display_message, sizeof(display_message), "DeadTime: %ins", CONFIG_DEAD_TIME_PWM);
|
||||
ssd1306_display_text(&dev, 4, display_message, strlen(display_message), cursor_position == 2);
|
||||
|
||||
//Back
|
||||
snprintf(display_message, sizeof(display_message), "Back");
|
||||
ssd1306_display_text(&dev, 5, display_message, strlen(display_message), cursor_position == 3);
|
||||
|
||||
//State
|
||||
getset_bridge_state();
|
||||
snprintf(display_message, sizeof(display_message), "State: %s",state_names[current_bridge_state]);
|
||||
ssd1306_display_text(&dev, 6, display_message, strlen(display_message), true);
|
||||
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void render_info_menu(){
|
||||
max_cursor_pos = 1;
|
||||
|
||||
//cur_U & Hall_A
|
||||
snprintf(display_message, sizeof(display_message), "U:%ldmA H_A:%c", get_current_ASC712(CONFIG_I_SENSE_U_ADC),get_Hall(CONFIG_HALL_A_GPIO)?'1':'0');
|
||||
ssd1306_display_text(&dev, 1, display_message, strlen(display_message), false);
|
||||
//cur_V & Hall_B
|
||||
snprintf(display_message, sizeof(display_message), "V:%ldmA H_B:%c", get_current_ASC712(CONFIG_I_SENSE_V_ADC),get_Hall(CONFIG_HALL_B_GPIO)?'1':'0');
|
||||
ssd1306_display_text(&dev, 2, display_message, strlen(display_message), false);
|
||||
//cur_W & Hall_C
|
||||
snprintf(display_message, sizeof(display_message), "W:%ldmA H_C:%c", get_current_ASC712(CONFIG_I_SENSE_W_ADC),get_Hall(CONFIG_HALL_C_GPIO)?'1':'0');
|
||||
ssd1306_display_text(&dev, 3, display_message, strlen(display_message), false);
|
||||
//Bridge Current & Speed
|
||||
snprintf(display_message, sizeof(display_message), "B:%ldmA SP.:%frpm", get_current_bridge(CONFIG_I_SENSE_ADC), get_speed_AB());
|
||||
ssd1306_display_text(&dev, 4, display_message, strlen(display_message), false);
|
||||
//Bridge Voltage & Torque
|
||||
snprintf(display_message, sizeof(display_message), "U_in:%ldmV Torq.:%ldmV", get_voltage_in(), get_torque());
|
||||
ssd1306_display_text(&dev, 5, display_message, strlen(display_message), false);
|
||||
//Left/right
|
||||
snprintf(display_message, sizeof(display_message), "Dir.:%s",
|
||||
(get_direction() == -1) ? "Error" :
|
||||
(get_direction() == 0) ? "Right" : "Left");
|
||||
ssd1306_display_text(&dev, 6, display_message, strlen(display_message), false);
|
||||
//Back
|
||||
snprintf(display_message, sizeof(display_message), "Back");
|
||||
ssd1306_display_text(&dev, 7, display_message, strlen(display_message), true);
|
||||
|
||||
|
||||
}
|
||||
|
||||
MenuState last_menu = MAIN_MENU; // Initialisiere mit dem Startmenü
|
||||
OutCombis last_out_combi = OUT_U_V;
|
||||
void menu_loop(){
|
||||
if(current_mode== BLDC_MODE){
|
||||
current_out_combi = get_output_combination(get_Hall_Combi());
|
||||
|
||||
if (current_out_combi != last_out_combi) {
|
||||
configure_mcpwm_output(current_out_combi);
|
||||
if(ShouldState){
|
||||
start_mcpwm_output();
|
||||
}
|
||||
last_out_combi = current_out_combi; // Update to the new out_combi
|
||||
}}
|
||||
|
||||
if(!in_editing){
|
||||
if (enc_in_counter<0){
|
||||
enc_in_counter = max_cursor_pos;
|
||||
}
|
||||
if (enc_in_counter> max_cursor_pos){
|
||||
enc_in_counter =0;
|
||||
}
|
||||
cursor_position = enc_in_counter;
|
||||
}
|
||||
if (current_menu != last_menu) {
|
||||
ssd1306_clear_screen(&dev, false); // Clear the screen on menu change
|
||||
last_menu = current_menu; // Update to the new menu state
|
||||
}
|
||||
switch (current_menu)
|
||||
{
|
||||
case MAIN_MENU:
|
||||
render_main_menu();
|
||||
break;
|
||||
case CONFIGURE_MENU:
|
||||
render_config_menu();
|
||||
break;
|
||||
case MORE_INFO_MENU:
|
||||
render_info_menu();
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
check_button_pressed();
|
||||
}
|
||||
142
old_functions.c
Executable file
142
old_functions.c
Executable file
@@ -0,0 +1,142 @@
|
||||
/*############################################*/
|
||||
/*################ PWM-Setup #################*/
|
||||
/*############################################*/
|
||||
|
||||
void set_PWM_Timer()
|
||||
{
|
||||
ledc_timer_config_t ledc_timer = {
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE,
|
||||
.timer_num = LEDC_TIMER_0,
|
||||
.duty_resolution = LEDC_TIMER_10_BIT,
|
||||
.freq_hz = CONFIG_FREQ_PWM,
|
||||
.clk_cfg = LEDC_AUTO_CLK
|
||||
};
|
||||
esp_err_t err = ledc_timer_config(&ledc_timer);
|
||||
if (err != ESP_OK) {
|
||||
printf("Fehler beim Konfigurieren des LEDC-Timers: %s\n", esp_err_to_name(err));
|
||||
return;
|
||||
}
|
||||
|
||||
}
|
||||
void set_PWM()
|
||||
{
|
||||
ledc_channel_config_t ledc_channel_HIN_U =
|
||||
{
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE, // Gleicher Modus wie beim Timer
|
||||
.channel = LEDC_CHANNEL_0, // Kanal 0 verwenden
|
||||
.timer_sel = LEDC_TIMER_0, // Timer 0 zuweisen
|
||||
.intr_type = LEDC_INTR_DISABLE, // Keine Interrupts
|
||||
.gpio_num = CONFIG_HIN_U_GPIO,
|
||||
.duty = 0, //
|
||||
.hpoint = 0 // Start des PWM-Signals
|
||||
};
|
||||
ledc_channel_config(&ledc_channel_HIN_U); // Kanal konfigurieren
|
||||
ledc_channel_config_t ledc_channel_HIN_V =
|
||||
{
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE, // Gleicher Modus wie beim Timer
|
||||
.channel = LEDC_CHANNEL_1, // Kanal 0 verwenden
|
||||
.timer_sel = LEDC_TIMER_0, // Timer 0 zuweisen
|
||||
.intr_type = LEDC_INTR_DISABLE, // Keine Interrupts
|
||||
.gpio_num = CONFIG_HIN_V_GPIO,
|
||||
.duty = 0, //
|
||||
.hpoint = 0 // Start des PWM-Signals
|
||||
};
|
||||
ledc_channel_config(&ledc_channel_HIN_V); // Kanal konfigurieren
|
||||
ledc_channel_config_t ledc_channel_HIN_W =
|
||||
{
|
||||
.speed_mode = LEDC_HIGH_SPEED_MODE, // Gleicher Modus wie beim Timer
|
||||
.channel = LEDC_CHANNEL_2, // Kanal 0 verwenden
|
||||
.timer_sel = LEDC_TIMER_0, // Timer 0 zuweisen
|
||||
.intr_type = LEDC_INTR_DISABLE, // Keine Interrupts
|
||||
.gpio_num = CONFIG_HIN_W_GPIO,
|
||||
.duty = 0, //
|
||||
.hpoint = 0 // Start des PWM-Signals
|
||||
};
|
||||
ledc_channel_config(&ledc_channel_HIN_W); // Kanal konfigurieren
|
||||
}
|
||||
void pwmStart(int PWM_CH, int Duty){
|
||||
ledc_set_duty(LEDC_HIGH_SPEED_MODE,PWM_CH, Duty);
|
||||
ledc_update_duty(LEDC_HIGH_SPEED_MODE,PWM_CH);
|
||||
}
|
||||
void pwmStop(int PWM_CH){
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, PWM_CH, 0);
|
||||
}
|
||||
void pwmStopAll(){
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, HIN_U_CH, 0);
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, HIN_V_CH, 0);
|
||||
ledc_stop(LEDC_HIGH_SPEED_MODE, HIN_W_CH, 0);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 0);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 0);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 0);
|
||||
}
|
||||
void U_V_start(int duty)
|
||||
{
|
||||
//HIN_V und LIN_U abschalten
|
||||
pwmStop(HIN_V_CH);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_U_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 1);
|
||||
}
|
||||
void V_U_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_V abschalten
|
||||
pwmStop(HIN_U_CH);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 0);
|
||||
//HIN_V und LIN_U einschalten
|
||||
pwmStart(HIN_V_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 1);
|
||||
}
|
||||
void U_W_start(int duty)
|
||||
{
|
||||
//HIN_W und LIN_U abschalten
|
||||
pwmStop(HIN_W_CH);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_W_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 1);
|
||||
}
|
||||
void W_U_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_W abschalten
|
||||
pwmStop(HIN_U_CH);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_W_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_U_GPIO, 1);
|
||||
}
|
||||
void V_W_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_W abschalten
|
||||
pwmStop(HIN_W_CH);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_V_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 1);
|
||||
}
|
||||
void W_V_start(int duty)
|
||||
{
|
||||
//HIN_U und LIN_W abschalten
|
||||
pwmStop(HIN_V_CH);
|
||||
gpio_set_level(CONFIG_LIN_W_GPIO, 0);
|
||||
//HIN_U und LIN_V einschalten
|
||||
pwmStart(HIN_W_CH, duty);
|
||||
gpio_set_level(CONFIG_LIN_V_GPIO, 1);
|
||||
}
|
||||
/*############################################*/
|
||||
/*################## MISC ####################*/
|
||||
/*############################################*/
|
||||
//Ausgelagert in Preprocessing python program, generate_pins_header.py
|
||||
void parse_3pins(const char *TAG, const char *pin_string, int *pins) {
|
||||
int pin_count = 0; // Jetzt ein Integer, keine Null-Pointer-Dereferenzierung
|
||||
char *token;
|
||||
char *pin_list = strdup(pin_string); // Kopie der String-Option
|
||||
|
||||
token = strtok(pin_list, ",");
|
||||
while (token != NULL && pin_count < 3) { // maximal 3 Pins
|
||||
pins[pin_count] = atoi(token); // Umwandlung in Integer
|
||||
pin_count++;
|
||||
token = strtok(NULL, ",");
|
||||
}
|
||||
free(pin_list); // Speicher freigeben
|
||||
}
|
||||
11
old_functions.h
Executable file
11
old_functions.h
Executable file
@@ -0,0 +1,11 @@
|
||||
void set_PWM_Timer();
|
||||
void set_PWM();
|
||||
void pwmStart(int PWM_CH,int Duty);
|
||||
void pwmStop(int PWM_CH);
|
||||
void pwmStopAll();
|
||||
void U_V_start(int duty);
|
||||
void V_U_start(int duty);
|
||||
void U_W_start(int duty);
|
||||
void W_U_start(int duty);
|
||||
void V_W_start(int duty);
|
||||
void W_V_start(int duty);
|
||||
9
parsed_pins.h
Normal file → Executable file
9
parsed_pins.h
Normal file → Executable file
@@ -1,4 +1,6 @@
|
||||
// Automatically generated file. Do not modify.
|
||||
#ifndef PARSED_PINS_H
|
||||
#define PARSED_PINS_H
|
||||
|
||||
#define CONFIG_I_SENSE_U_ADC 6
|
||||
#define CONFIG_I_SENSE_V_ADC 3
|
||||
@@ -16,11 +18,12 @@
|
||||
#define CONFIG_HALL_B_GPIO 16
|
||||
#define CONFIG_HALL_C_GPIO 17
|
||||
|
||||
#define CONFIG_IN_ENC_A_GPIO 3
|
||||
#define CONFIG_IN_ENC_B_GPIO 2
|
||||
#define CONFIG_IN_ENC_BUT_GPIO 23
|
||||
#define CONFIG_IN_ENC_A_GPIO 23
|
||||
#define CONFIG_IN_ENC_B_GPIO 1
|
||||
#define CONFIG_IN_ENC_BUT_GPIO 3
|
||||
|
||||
#define CONFIG_EXT_ENC_INDX_GPIO 16
|
||||
#define CONFIG_EXT_ENC_LEFT_GPIO 18
|
||||
#define CONFIG_EXT_ENC_RIGHT_GPIO 5
|
||||
|
||||
#endif
|
||||
337
sdkconfig
337
sdkconfig
@@ -1,6 +1,6 @@
|
||||
#
|
||||
# Automatically generated file. DO NOT EDIT.
|
||||
# Espressif IoT Development Framework (ESP-IDF) 5.2.3 Project Configuration
|
||||
# Espressif IoT Development Framework (ESP-IDF) 5.3.0 Project Configuration
|
||||
#
|
||||
CONFIG_SOC_BROWNOUT_RESET_SUPPORTED="Not determined"
|
||||
CONFIG_SOC_TWAI_BRP_DIV_SUPPORTED="Not determined"
|
||||
@@ -14,6 +14,7 @@ CONFIG_SOC_GPTIMER_SUPPORTED=y
|
||||
CONFIG_SOC_SDMMC_HOST_SUPPORTED=y
|
||||
CONFIG_SOC_BT_SUPPORTED=y
|
||||
CONFIG_SOC_PCNT_SUPPORTED=y
|
||||
CONFIG_SOC_PHY_SUPPORTED=y
|
||||
CONFIG_SOC_WIFI_SUPPORTED=y
|
||||
CONFIG_SOC_SDIO_SLAVE_SUPPORTED=y
|
||||
CONFIG_SOC_TWAI_SUPPORTED=y
|
||||
@@ -43,6 +44,11 @@ CONFIG_SOC_CLK_TREE_SUPPORTED=y
|
||||
CONFIG_SOC_MPU_SUPPORTED=y
|
||||
CONFIG_SOC_WDT_SUPPORTED=y
|
||||
CONFIG_SOC_SPI_FLASH_SUPPORTED=y
|
||||
CONFIG_SOC_RNG_SUPPORTED=y
|
||||
CONFIG_SOC_LIGHT_SLEEP_SUPPORTED=y
|
||||
CONFIG_SOC_DEEP_SLEEP_SUPPORTED=y
|
||||
CONFIG_SOC_LP_PERIPH_SHARE_INTERRUPT=y
|
||||
CONFIG_SOC_PM_SUPPORTED=y
|
||||
CONFIG_SOC_DPORT_WORKAROUND_DIS_INTERRUPT_LVL=5
|
||||
CONFIG_SOC_XTAL_SUPPORT_26M=y
|
||||
CONFIG_SOC_XTAL_SUPPORT_40M=y
|
||||
@@ -84,7 +90,9 @@ CONFIG_SOC_GPIO_IN_RANGE_MAX=39
|
||||
CONFIG_SOC_GPIO_OUT_RANGE_MAX=33
|
||||
CONFIG_SOC_GPIO_VALID_DIGITAL_IO_PAD_MASK=0xEF0FEA
|
||||
CONFIG_SOC_GPIO_CLOCKOUT_BY_IO_MUX=y
|
||||
CONFIG_SOC_GPIO_CLOCKOUT_CHANNEL_NUM=3
|
||||
CONFIG_SOC_I2C_NUM=2
|
||||
CONFIG_SOC_HP_I2C_NUM=2
|
||||
CONFIG_SOC_I2C_FIFO_LEN=32
|
||||
CONFIG_SOC_I2C_CMD_REG_NUM=16
|
||||
CONFIG_SOC_I2C_SUPPORT_SLAVE=y
|
||||
@@ -164,9 +172,9 @@ CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2
|
||||
CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64
|
||||
CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4
|
||||
CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y
|
||||
CONFIG_SOC_TOUCH_VERSION_1=y
|
||||
CONFIG_SOC_TOUCH_SENSOR_VERSION=1
|
||||
CONFIG_SOC_TOUCH_SENSOR_NUM=10
|
||||
CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF
|
||||
CONFIG_SOC_TOUCH_SAMPLER_NUM=1
|
||||
CONFIG_SOC_TWAI_CONTROLLER_NUM=1
|
||||
CONFIG_SOC_TWAI_BRP_MIN=2
|
||||
CONFIG_SOC_TWAI_CLK_SUPPORT_APB=y
|
||||
@@ -222,14 +230,16 @@ CONFIG_SOC_BLE_SUPPORTED=y
|
||||
CONFIG_SOC_BLE_MESH_SUPPORTED=y
|
||||
CONFIG_SOC_BT_CLASSIC_SUPPORTED=y
|
||||
CONFIG_SOC_BLUFI_SUPPORTED=y
|
||||
CONFIG_SOC_BT_H2C_ENC_KEY_CTRL_ENH_VSC_SUPPORTED=y
|
||||
CONFIG_SOC_ULP_HAS_ADC=y
|
||||
CONFIG_SOC_PHY_COMBO_MODULE=y
|
||||
CONFIG_SOC_EMAC_RMII_CLK_OUT_INTERNAL_LOOPBACK=y
|
||||
CONFIG_IDF_CMAKE=y
|
||||
CONFIG_IDF_TOOLCHAIN="gcc"
|
||||
CONFIG_IDF_TARGET_ARCH_XTENSA=y
|
||||
CONFIG_IDF_TARGET_ARCH="xtensa"
|
||||
CONFIG_IDF_TARGET="esp32"
|
||||
CONFIG_IDF_INIT_VERSION="5.2.3"
|
||||
CONFIG_IDF_INIT_VERSION="5.3.0"
|
||||
CONFIG_IDF_TARGET_ESP32=y
|
||||
CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000
|
||||
|
||||
@@ -319,9 +329,13 @@ CONFIG_ESP_ROM_HAS_MZ_CRC32=y
|
||||
CONFIG_ESP_ROM_HAS_JPEG_DECODE=y
|
||||
CONFIG_ESP_ROM_HAS_UART_BUF_SWITCH=y
|
||||
CONFIG_ESP_ROM_NEEDS_SWSETUP_WORKAROUND=y
|
||||
CONFIG_ESP_ROM_HAS_NEWLIB=y
|
||||
CONFIG_ESP_ROM_HAS_NEWLIB_NANO_FORMAT=y
|
||||
CONFIG_ESP_ROM_HAS_NEWLIB_32BIT_TIME=y
|
||||
CONFIG_ESP_ROM_HAS_SW_FLOAT=y
|
||||
CONFIG_ESP_ROM_USB_OTG_NUM=-1
|
||||
CONFIG_ESP_ROM_USB_SERIAL_DEVICE_NUM=-1
|
||||
CONFIG_ESP_ROM_SUPPORT_DEEP_SLEEP_WAKEUP_STUB=y
|
||||
|
||||
#
|
||||
# Serial flasher config
|
||||
@@ -373,6 +387,8 @@ CONFIG_PARTITION_TABLE_MD5=y
|
||||
#
|
||||
# DIY Power PCB Configuration
|
||||
#
|
||||
CONFIG_V2=y
|
||||
# CONFIG_V1 is not set
|
||||
CONFIG_ENV_GPIO_RANGE_MIN=0
|
||||
CONFIG_ENV_GPIO_RANGE_MAX=39
|
||||
CONFIG_ENV_GPIO_IN_RANGE_MAX=39
|
||||
@@ -391,18 +407,24 @@ CONFIG_TORQUE_ADC=4
|
||||
# Highside pin configurations (HIN)
|
||||
#
|
||||
CONFIG_HIN_U_V_W_GPIO="26, 14, 13"
|
||||
CONFIG_ENABLE_PWM_HIN=y
|
||||
CONFIG_FREQ_PWM_HIN=20000
|
||||
CONFIG_DUTY_PWM_HIN=50
|
||||
# end of Highside pin configurations (HIN)
|
||||
|
||||
#
|
||||
# Lowside pin configurations (LIN)
|
||||
#
|
||||
CONFIG_LIN_U_V_W_GPIO="25, 27, 12"
|
||||
# CONFIG_ENABLE_PWM_LIN is not set
|
||||
# end of Lowside pin configurations (LIN)
|
||||
|
||||
#
|
||||
# PWM configuration
|
||||
#
|
||||
CONFIG_ENABLE_PWM=y
|
||||
CONFIG_TIMER_BASE_FREQ=40000000
|
||||
CONFIG_FREQ_PWM=20000
|
||||
CONFIG_DUTY_PWM=50
|
||||
CONFIG_DEAD_TIME_PWM=0
|
||||
# end of PWM configuration
|
||||
|
||||
#
|
||||
# Hall Sensor pin configurations
|
||||
#
|
||||
@@ -412,13 +434,13 @@ CONFIG_HALL_A_B_C_GPIO="4, 16, 17"
|
||||
#
|
||||
# Input pin configurations
|
||||
#
|
||||
CONFIG_IN_ENCODER_GPIO="3, 2, 23"
|
||||
CONFIG_BUTTON_GPIO=1
|
||||
CONFIG_IN_ENCODER_GPIO="23,1,3"
|
||||
CONFIG_IN_ENCODER_GPIO_V2="23, 1, 3"
|
||||
CONFIG_IN_ENCODER_DEBOUNCE_TIME=500
|
||||
CONFIG_ESP_LED=2
|
||||
CONFIG_EXT_ENCODER_GPIO="16, 18, 5"
|
||||
CONFIG_RFE_GPIO=15
|
||||
# end of Input pin configurations
|
||||
|
||||
CONFIG_BLINK_PERIOD=1000
|
||||
# end of DIY Power PCB Configuration
|
||||
|
||||
#
|
||||
@@ -429,11 +451,11 @@ CONFIG_I2C_INTERFACE=y
|
||||
# CONFIG_SPI_INTERFACE is not set
|
||||
# CONFIG_SSD1306_128x32 is not set
|
||||
CONFIG_SSD1306_128x64=y
|
||||
CONFIG_OFFSETX=0
|
||||
CONFIG_OFFSETX=2
|
||||
# CONFIG_FLIP is not set
|
||||
CONFIG_SCL_GPIO=22
|
||||
CONFIG_SDA_GPIO=21
|
||||
CONFIG_RESET_GPIO=15
|
||||
CONFIG_RESET_GPIO=-1
|
||||
CONFIG_I2C_PORT_0=y
|
||||
# CONFIG_I2C_PORT_1 is not set
|
||||
# CONFIG_LEGACY_DRIVER is not set
|
||||
@@ -492,35 +514,16 @@ CONFIG_APPTRACE_LOCK_ENABLE=y
|
||||
CONFIG_BT_ALARM_MAX_NUM=50
|
||||
# end of Bluetooth
|
||||
|
||||
#
|
||||
# Console Library
|
||||
#
|
||||
# CONFIG_CONSOLE_SORTED_HELP is not set
|
||||
# end of Console Library
|
||||
|
||||
#
|
||||
# Driver Configurations
|
||||
#
|
||||
|
||||
#
|
||||
# Legacy ADC Configuration
|
||||
#
|
||||
CONFIG_ADC_DISABLE_DAC=y
|
||||
# CONFIG_ADC_SUPPRESS_DEPRECATE_WARN is not set
|
||||
|
||||
#
|
||||
# Legacy ADC Calibration Configuration
|
||||
#
|
||||
CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y
|
||||
CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y
|
||||
CONFIG_ADC_CAL_LUT_ENABLE=y
|
||||
# CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy ADC Calibration Configuration
|
||||
# end of Legacy ADC Configuration
|
||||
|
||||
#
|
||||
# SPI Configuration
|
||||
#
|
||||
# CONFIG_SPI_MASTER_IN_IRAM is not set
|
||||
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
|
||||
|
||||
#
|
||||
# TWAI Configuration
|
||||
#
|
||||
@@ -533,93 +536,62 @@ CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM=y
|
||||
# end of TWAI Configuration
|
||||
|
||||
#
|
||||
# UART Configuration
|
||||
# Legacy ADC Driver Configuration
|
||||
#
|
||||
# CONFIG_UART_ISR_IN_IRAM is not set
|
||||
# end of UART Configuration
|
||||
CONFIG_ADC_DISABLE_DAC=y
|
||||
# CONFIG_ADC_SUPPRESS_DEPRECATE_WARN is not set
|
||||
|
||||
#
|
||||
# GPIO Configuration
|
||||
# Legacy ADC Calibration Configuration
|
||||
#
|
||||
# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set
|
||||
# CONFIG_GPIO_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of GPIO Configuration
|
||||
CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y
|
||||
CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y
|
||||
CONFIG_ADC_CAL_LUT_ENABLE=y
|
||||
# CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy ADC Calibration Configuration
|
||||
# end of Legacy ADC Driver Configuration
|
||||
|
||||
#
|
||||
# Sigma Delta Modulator Configuration
|
||||
# Legacy DAC Driver Configurations
|
||||
#
|
||||
# CONFIG_SDM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_SDM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_SDM_ENABLE_DEBUG_LOG is not set
|
||||
# end of Sigma Delta Modulator Configuration
|
||||
|
||||
#
|
||||
# GPTimer Configuration
|
||||
#
|
||||
CONFIG_GPTIMER_ISR_HANDLER_IN_IRAM=y
|
||||
# CONFIG_GPTIMER_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_GPTIMER_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_GPTIMER_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_GPTIMER_ENABLE_DEBUG_LOG is not set
|
||||
# end of GPTimer Configuration
|
||||
|
||||
#
|
||||
# PCNT Configuration
|
||||
#
|
||||
# CONFIG_PCNT_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_PCNT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_PCNT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_PCNT_ENABLE_DEBUG_LOG is not set
|
||||
# end of PCNT Configuration
|
||||
|
||||
#
|
||||
# RMT Configuration
|
||||
#
|
||||
# CONFIG_RMT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_RMT_RECV_FUNC_IN_IRAM is not set
|
||||
# CONFIG_RMT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_RMT_ENABLE_DEBUG_LOG is not set
|
||||
# end of RMT Configuration
|
||||
|
||||
#
|
||||
# MCPWM Configuration
|
||||
#
|
||||
# CONFIG_MCPWM_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_MCPWM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_MCPWM_ENABLE_DEBUG_LOG is not set
|
||||
# end of MCPWM Configuration
|
||||
|
||||
#
|
||||
# I2S Configuration
|
||||
#
|
||||
# CONFIG_I2S_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2S_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_I2S_ENABLE_DEBUG_LOG is not set
|
||||
# end of I2S Configuration
|
||||
|
||||
#
|
||||
# DAC Configuration
|
||||
#
|
||||
# CONFIG_DAC_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_DAC_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_DAC_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_DAC_ENABLE_DEBUG_LOG is not set
|
||||
CONFIG_DAC_DMA_AUTO_16BIT_ALIGN=y
|
||||
# end of DAC Configuration
|
||||
# end of Legacy DAC Driver Configurations
|
||||
|
||||
#
|
||||
# LEDC Configuration
|
||||
# Legacy MCPWM Driver Configurations
|
||||
#
|
||||
# CONFIG_LEDC_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of LEDC Configuration
|
||||
# CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy MCPWM Driver Configurations
|
||||
|
||||
#
|
||||
# I2C Configuration
|
||||
# Legacy Timer Group Driver Configurations
|
||||
#
|
||||
# CONFIG_I2C_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2C_ENABLE_DEBUG_LOG is not set
|
||||
# end of I2C Configuration
|
||||
# CONFIG_GPTIMER_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy Timer Group Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy RMT Driver Configurations
|
||||
#
|
||||
# CONFIG_RMT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy RMT Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy I2S Driver Configurations
|
||||
#
|
||||
# CONFIG_I2S_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy I2S Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy PCNT Driver Configurations
|
||||
#
|
||||
# CONFIG_PCNT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy PCNT Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy SDM Driver Configurations
|
||||
#
|
||||
# CONFIG_SDM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy SDM Driver Configurations
|
||||
# end of Driver Configurations
|
||||
|
||||
#
|
||||
@@ -639,7 +611,9 @@ CONFIG_EFUSE_MAX_BLK_LEN=192
|
||||
CONFIG_ESP_TLS_USING_MBEDTLS=y
|
||||
# CONFIG_ESP_TLS_USE_SECURE_ELEMENT is not set
|
||||
# CONFIG_ESP_TLS_CLIENT_SESSION_TICKETS is not set
|
||||
# CONFIG_ESP_TLS_SERVER is not set
|
||||
# CONFIG_ESP_TLS_SERVER_SESSION_TICKETS is not set
|
||||
# CONFIG_ESP_TLS_SERVER_CERT_SELECT_HOOK is not set
|
||||
# CONFIG_ESP_TLS_SERVER_MIN_AUTH_MODE_OPTIONAL is not set
|
||||
# CONFIG_ESP_TLS_PSK_VERIFICATION is not set
|
||||
# CONFIG_ESP_TLS_INSECURE is not set
|
||||
# end of ESP-TLS
|
||||
@@ -659,11 +633,13 @@ CONFIG_ADC_CALI_LUT_ENABLE=y
|
||||
# end of ADC Calibration Configurations
|
||||
|
||||
CONFIG_ADC_DISABLE_DAC_OUTPUT=y
|
||||
# CONFIG_ADC_ENABLE_DEBUG_LOG is not set
|
||||
# end of ADC and ADC Calibration
|
||||
|
||||
#
|
||||
# Wireless Coexistence
|
||||
#
|
||||
CONFIG_ESP_COEX_ENABLED=y
|
||||
# end of Wireless Coexistence
|
||||
|
||||
#
|
||||
@@ -672,6 +648,97 @@ CONFIG_ADC_DISABLE_DAC_OUTPUT=y
|
||||
CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
||||
# end of Common ESP-related
|
||||
|
||||
#
|
||||
# ESP-Driver:DAC Configurations
|
||||
#
|
||||
# CONFIG_DAC_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_DAC_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_DAC_ENABLE_DEBUG_LOG is not set
|
||||
CONFIG_DAC_DMA_AUTO_16BIT_ALIGN=y
|
||||
# end of ESP-Driver:DAC Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:GPIO Configurations
|
||||
#
|
||||
# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set
|
||||
# CONFIG_GPIO_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of ESP-Driver:GPIO Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:GPTimer Configurations
|
||||
#
|
||||
CONFIG_GPTIMER_ISR_HANDLER_IN_IRAM=y
|
||||
# CONFIG_GPTIMER_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_GPTIMER_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_GPTIMER_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:GPTimer Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:I2C Configurations
|
||||
#
|
||||
# CONFIG_I2C_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2C_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:I2C Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:I2S Configurations
|
||||
#
|
||||
# CONFIG_I2S_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2S_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:I2S Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:LEDC Configurations
|
||||
#
|
||||
# CONFIG_LEDC_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of ESP-Driver:LEDC Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:MCPWM Configurations
|
||||
#
|
||||
# CONFIG_MCPWM_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_MCPWM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_MCPWM_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:MCPWM Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:PCNT Configurations
|
||||
#
|
||||
# CONFIG_PCNT_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_PCNT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_PCNT_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:PCNT Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:RMT Configurations
|
||||
#
|
||||
# CONFIG_RMT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_RMT_RECV_FUNC_IN_IRAM is not set
|
||||
# CONFIG_RMT_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:RMT Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:Sigma Delta Modulator Configurations
|
||||
#
|
||||
# CONFIG_SDM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_SDM_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:Sigma Delta Modulator Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:SPI Configurations
|
||||
#
|
||||
# CONFIG_SPI_MASTER_IN_IRAM is not set
|
||||
CONFIG_SPI_MASTER_ISR_IN_IRAM=y
|
||||
# CONFIG_SPI_SLAVE_IN_IRAM is not set
|
||||
CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||
# end of ESP-Driver:SPI Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:UART Configurations
|
||||
#
|
||||
# CONFIG_UART_ISR_IN_IRAM is not set
|
||||
# end of ESP-Driver:UART Configurations
|
||||
|
||||
#
|
||||
# Ethernet
|
||||
#
|
||||
@@ -716,6 +783,7 @@ CONFIG_ESP_GDBSTUB_MAX_TASKS=32
|
||||
CONFIG_ESP_HTTP_CLIENT_ENABLE_HTTPS=y
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_BASIC_AUTH is not set
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_DIGEST_AUTH is not set
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_CUSTOM_TRANSPORT is not set
|
||||
# end of ESP HTTP client
|
||||
|
||||
#
|
||||
@@ -765,12 +833,6 @@ CONFIG_ESP_REV_MIN_FULL=0
|
||||
#
|
||||
CONFIG_ESP32_REV_MAX_FULL=399
|
||||
CONFIG_ESP_REV_MAX_FULL=399
|
||||
CONFIG_ESP_EFUSE_BLOCK_REV_MIN_FULL=0
|
||||
CONFIG_ESP_EFUSE_BLOCK_REV_MAX_FULL=99
|
||||
|
||||
#
|
||||
# Maximum Supported ESP32 eFuse Block Revision (eFuse Block Rev v0.99)
|
||||
#
|
||||
# end of Chip revision
|
||||
|
||||
#
|
||||
@@ -781,6 +843,7 @@ CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y
|
||||
CONFIG_ESP_MAC_UNIVERSAL_MAC_ADDRESSES_FOUR=y
|
||||
CONFIG_ESP_MAC_UNIVERSAL_MAC_ADDRESSES=4
|
||||
# CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO is not set
|
||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR=y
|
||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4
|
||||
@@ -826,6 +889,8 @@ CONFIG_XTAL_FREQ_40=y
|
||||
# CONFIG_XTAL_FREQ_AUTO is not set
|
||||
CONFIG_XTAL_FREQ=40
|
||||
# end of Main XTAL Config
|
||||
|
||||
CONFIG_ESP_SPI_BUS_LOCK_ISR_FUNCS_IN_IRAM=y
|
||||
# end of Hardware Settings
|
||||
|
||||
#
|
||||
@@ -854,7 +919,6 @@ CONFIG_ESP_NETIF_USES_TCPIP_WITH_BSD_API=y
|
||||
# CONFIG_ESP_NETIF_RECEIVE_REPORT_ERRORS is not set
|
||||
# CONFIG_ESP_NETIF_L2_TAP is not set
|
||||
# CONFIG_ESP_NETIF_BRIDGE_EN is not set
|
||||
# CONFIG_ESP_NETIF_SET_DNS_PER_DEFAULT_NETIF is not set
|
||||
# end of ESP NETIF Adapter
|
||||
|
||||
#
|
||||
@@ -865,6 +929,7 @@ CONFIG_ESP_NETIF_USES_TCPIP_WITH_BSD_API=y
|
||||
#
|
||||
# PHY
|
||||
#
|
||||
CONFIG_ESP_PHY_ENABLED=y
|
||||
CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y
|
||||
# CONFIG_ESP_PHY_INIT_DATA_IN_PARTITION is not set
|
||||
CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20
|
||||
@@ -946,6 +1011,7 @@ CONFIG_ESP_CONSOLE_UART_DEFAULT=y
|
||||
# CONFIG_ESP_CONSOLE_NONE is not set
|
||||
CONFIG_ESP_CONSOLE_UART=y
|
||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||
CONFIG_ESP_CONSOLE_ROM_SERIAL_PORT_NUM=0
|
||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||
CONFIG_ESP_INT_WDT=y
|
||||
CONFIG_ESP_INT_WDT_TIMEOUT_MS=300
|
||||
@@ -990,7 +1056,7 @@ CONFIG_ESP_IPC_ISR_ENABLE=y
|
||||
# end of IPC (Inter-Processor Call)
|
||||
|
||||
#
|
||||
# High resolution timer (esp_timer)
|
||||
# ESP Timer (High Resolution Timer)
|
||||
#
|
||||
# CONFIG_ESP_TIMER_PROFILING is not set
|
||||
CONFIG_ESP_TIME_FUNCS_USE_RTC_TIMER=y
|
||||
@@ -1000,11 +1066,10 @@ CONFIG_ESP_TIMER_INTERRUPT_LEVEL=1
|
||||
# CONFIG_ESP_TIMER_SHOW_EXPERIMENTAL is not set
|
||||
CONFIG_ESP_TIMER_TASK_AFFINITY=0x0
|
||||
CONFIG_ESP_TIMER_TASK_AFFINITY_CPU0=y
|
||||
CONFIG_ESP_TIMER_ISR_AFFINITY=0x1
|
||||
CONFIG_ESP_TIMER_ISR_AFFINITY_CPU0=y
|
||||
# CONFIG_ESP_TIMER_SUPPORTS_ISR_DISPATCH_METHOD is not set
|
||||
CONFIG_ESP_TIMER_IMPL_TG0_LAC=y
|
||||
# end of High resolution timer (esp_timer)
|
||||
# end of ESP Timer (High Resolution Timer)
|
||||
|
||||
#
|
||||
# Wi-Fi
|
||||
@@ -1115,6 +1180,8 @@ CONFIG_FATFS_PER_FILE_CACHE=y
|
||||
# CONFIG_FATFS_USE_FASTSEEK is not set
|
||||
CONFIG_FATFS_VFS_FSTAT_BLKSIZE=0
|
||||
# CONFIG_FATFS_IMMEDIATE_FSYNC is not set
|
||||
# CONFIG_FATFS_USE_LABEL is not set
|
||||
CONFIG_FATFS_LINK_LOCK=y
|
||||
# end of FAT Filesystem support
|
||||
|
||||
#
|
||||
@@ -1136,14 +1203,18 @@ CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536
|
||||
# CONFIG_FREERTOS_USE_TICK_HOOK is not set
|
||||
CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16
|
||||
# CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY is not set
|
||||
CONFIG_FREERTOS_USE_TIMERS=y
|
||||
CONFIG_FREERTOS_TIMER_SERVICE_TASK_NAME="Tmr Svc"
|
||||
# CONFIG_FREERTOS_TIMER_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_FREERTOS_TIMER_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_FREERTOS_TIMER_TASK_NO_AFFINITY=y
|
||||
CONFIG_FREERTOS_TIMER_SERVICE_TASK_CORE_AFFINITY=0x7FFFFFFF
|
||||
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_TASK_NOTIFICATION_ARRAY_ENTRIES=1
|
||||
# CONFIG_FREERTOS_USE_TRACE_FACILITY is not set
|
||||
# CONFIG_FREERTOS_USE_LIST_DATA_INTEGRITY_CHECK_BYTES is not set
|
||||
# CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS is not set
|
||||
# CONFIG_FREERTOS_USE_APPLICATION_TASK_TAG is not set
|
||||
# end of Kernel
|
||||
@@ -1174,6 +1245,7 @@ CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y
|
||||
CONFIG_FREERTOS_DEBUG_OCDAWARE=y
|
||||
CONFIG_FREERTOS_ENABLE_TASK_SNAPSHOT=y
|
||||
CONFIG_FREERTOS_PLACE_SNAPSHOT_FUNS_INTO_FLASH=y
|
||||
CONFIG_FREERTOS_NUMBER_OF_CORES=2
|
||||
# end of FreeRTOS
|
||||
|
||||
#
|
||||
@@ -1301,6 +1373,7 @@ CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000
|
||||
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5760
|
||||
CONFIG_LWIP_TCP_WND_DEFAULT=5760
|
||||
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
||||
CONFIG_LWIP_TCP_ACCEPTMBOX_SIZE=6
|
||||
CONFIG_LWIP_TCP_QUEUE_OOSEQ=y
|
||||
CONFIG_LWIP_TCP_OOSEQ_TIMEOUT=6
|
||||
CONFIG_LWIP_TCP_OOSEQ_MAX_PBUFS=4
|
||||
@@ -1331,9 +1404,6 @@ CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_PREFIXES=5
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_ROUTERS=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_DESTINATIONS=10
|
||||
# CONFIG_LWIP_PPP_SUPPORT is not set
|
||||
CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5
|
||||
@@ -1359,15 +1429,15 @@ CONFIG_LWIP_MAX_RAW_PCBS=16
|
||||
CONFIG_LWIP_SNTP_MAX_SERVERS=1
|
||||
# CONFIG_LWIP_DHCP_GET_NTP_SRV is not set
|
||||
CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000
|
||||
CONFIG_LWIP_SNTP_STARTUP_DELAY=y
|
||||
CONFIG_LWIP_SNTP_MAXIMUM_STARTUP_DELAY=5000
|
||||
# end of SNTP
|
||||
|
||||
#
|
||||
# DNS
|
||||
#
|
||||
CONFIG_LWIP_DNS_MAX_HOST_IP=1
|
||||
CONFIG_LWIP_DNS_MAX_SERVERS=3
|
||||
# CONFIG_LWIP_FALLBACK_DNS_SERVER_SUPPORT is not set
|
||||
# CONFIG_LWIP_DNS_SETSERVER_WITH_NETIF is not set
|
||||
# end of DNS
|
||||
|
||||
CONFIG_LWIP_BRIDGEIF_MAX_PORTS=7
|
||||
@@ -1430,13 +1500,14 @@ 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
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEPRECATED_LIST is not set
|
||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200
|
||||
# end of Certificate Bundle
|
||||
|
||||
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
||||
CONFIG_MBEDTLS_CMAC_C=y
|
||||
CONFIG_MBEDTLS_HARDWARE_AES=y
|
||||
# CONFIG_MBEDTLS_GCM_SUPPORT_NON_AES_CIPHER is not set
|
||||
CONFIG_MBEDTLS_GCM_SUPPORT_NON_AES_CIPHER=y
|
||||
CONFIG_MBEDTLS_HARDWARE_MPI=y
|
||||
# CONFIG_MBEDTLS_LARGE_KEY_SOFTWARE_MPI is not set
|
||||
CONFIG_MBEDTLS_HARDWARE_SHA=y
|
||||
@@ -1639,6 +1710,7 @@ CONFIG_SPI_FLASH_BROWNOUT_RESET=y
|
||||
#
|
||||
# Features here require specific hardware (READ DOCS FIRST!)
|
||||
#
|
||||
CONFIG_SPI_FLASH_SUSPEND_TSUS_VAL_US=50
|
||||
# end of Optional and Experimental Features (READ DOCS FIRST)
|
||||
# end of Main Flash configuration
|
||||
|
||||
@@ -1733,6 +1805,11 @@ CONFIG_WS_BUFFER_SIZE=1024
|
||||
# Ultra Low Power (ULP) Co-processor
|
||||
#
|
||||
# CONFIG_ULP_COPROC_ENABLED is not set
|
||||
|
||||
#
|
||||
# ULP Debugging Options
|
||||
#
|
||||
# end of ULP Debugging Options
|
||||
# end of Ultra Low Power (ULP) Co-processor
|
||||
|
||||
#
|
||||
|
||||
337
sdkconfig.old
337
sdkconfig.old
@@ -1,6 +1,6 @@
|
||||
#
|
||||
# Automatically generated file. DO NOT EDIT.
|
||||
# Espressif IoT Development Framework (ESP-IDF) 5.2.3 Project Configuration
|
||||
# Espressif IoT Development Framework (ESP-IDF) 5.3.0 Project Configuration
|
||||
#
|
||||
CONFIG_SOC_BROWNOUT_RESET_SUPPORTED="Not determined"
|
||||
CONFIG_SOC_TWAI_BRP_DIV_SUPPORTED="Not determined"
|
||||
@@ -14,6 +14,7 @@ CONFIG_SOC_GPTIMER_SUPPORTED=y
|
||||
CONFIG_SOC_SDMMC_HOST_SUPPORTED=y
|
||||
CONFIG_SOC_BT_SUPPORTED=y
|
||||
CONFIG_SOC_PCNT_SUPPORTED=y
|
||||
CONFIG_SOC_PHY_SUPPORTED=y
|
||||
CONFIG_SOC_WIFI_SUPPORTED=y
|
||||
CONFIG_SOC_SDIO_SLAVE_SUPPORTED=y
|
||||
CONFIG_SOC_TWAI_SUPPORTED=y
|
||||
@@ -43,6 +44,11 @@ CONFIG_SOC_CLK_TREE_SUPPORTED=y
|
||||
CONFIG_SOC_MPU_SUPPORTED=y
|
||||
CONFIG_SOC_WDT_SUPPORTED=y
|
||||
CONFIG_SOC_SPI_FLASH_SUPPORTED=y
|
||||
CONFIG_SOC_RNG_SUPPORTED=y
|
||||
CONFIG_SOC_LIGHT_SLEEP_SUPPORTED=y
|
||||
CONFIG_SOC_DEEP_SLEEP_SUPPORTED=y
|
||||
CONFIG_SOC_LP_PERIPH_SHARE_INTERRUPT=y
|
||||
CONFIG_SOC_PM_SUPPORTED=y
|
||||
CONFIG_SOC_DPORT_WORKAROUND_DIS_INTERRUPT_LVL=5
|
||||
CONFIG_SOC_XTAL_SUPPORT_26M=y
|
||||
CONFIG_SOC_XTAL_SUPPORT_40M=y
|
||||
@@ -84,7 +90,9 @@ CONFIG_SOC_GPIO_IN_RANGE_MAX=39
|
||||
CONFIG_SOC_GPIO_OUT_RANGE_MAX=33
|
||||
CONFIG_SOC_GPIO_VALID_DIGITAL_IO_PAD_MASK=0xEF0FEA
|
||||
CONFIG_SOC_GPIO_CLOCKOUT_BY_IO_MUX=y
|
||||
CONFIG_SOC_GPIO_CLOCKOUT_CHANNEL_NUM=3
|
||||
CONFIG_SOC_I2C_NUM=2
|
||||
CONFIG_SOC_HP_I2C_NUM=2
|
||||
CONFIG_SOC_I2C_FIFO_LEN=32
|
||||
CONFIG_SOC_I2C_CMD_REG_NUM=16
|
||||
CONFIG_SOC_I2C_SUPPORT_SLAVE=y
|
||||
@@ -164,9 +172,9 @@ CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2
|
||||
CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64
|
||||
CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4
|
||||
CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y
|
||||
CONFIG_SOC_TOUCH_VERSION_1=y
|
||||
CONFIG_SOC_TOUCH_SENSOR_VERSION=1
|
||||
CONFIG_SOC_TOUCH_SENSOR_NUM=10
|
||||
CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF
|
||||
CONFIG_SOC_TOUCH_SAMPLER_NUM=1
|
||||
CONFIG_SOC_TWAI_CONTROLLER_NUM=1
|
||||
CONFIG_SOC_TWAI_BRP_MIN=2
|
||||
CONFIG_SOC_TWAI_CLK_SUPPORT_APB=y
|
||||
@@ -222,14 +230,16 @@ CONFIG_SOC_BLE_SUPPORTED=y
|
||||
CONFIG_SOC_BLE_MESH_SUPPORTED=y
|
||||
CONFIG_SOC_BT_CLASSIC_SUPPORTED=y
|
||||
CONFIG_SOC_BLUFI_SUPPORTED=y
|
||||
CONFIG_SOC_BT_H2C_ENC_KEY_CTRL_ENH_VSC_SUPPORTED=y
|
||||
CONFIG_SOC_ULP_HAS_ADC=y
|
||||
CONFIG_SOC_PHY_COMBO_MODULE=y
|
||||
CONFIG_SOC_EMAC_RMII_CLK_OUT_INTERNAL_LOOPBACK=y
|
||||
CONFIG_IDF_CMAKE=y
|
||||
CONFIG_IDF_TOOLCHAIN="gcc"
|
||||
CONFIG_IDF_TARGET_ARCH_XTENSA=y
|
||||
CONFIG_IDF_TARGET_ARCH="xtensa"
|
||||
CONFIG_IDF_TARGET="esp32"
|
||||
CONFIG_IDF_INIT_VERSION="5.2.3"
|
||||
CONFIG_IDF_INIT_VERSION="5.3.0"
|
||||
CONFIG_IDF_TARGET_ESP32=y
|
||||
CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000
|
||||
|
||||
@@ -319,9 +329,13 @@ CONFIG_ESP_ROM_HAS_MZ_CRC32=y
|
||||
CONFIG_ESP_ROM_HAS_JPEG_DECODE=y
|
||||
CONFIG_ESP_ROM_HAS_UART_BUF_SWITCH=y
|
||||
CONFIG_ESP_ROM_NEEDS_SWSETUP_WORKAROUND=y
|
||||
CONFIG_ESP_ROM_HAS_NEWLIB=y
|
||||
CONFIG_ESP_ROM_HAS_NEWLIB_NANO_FORMAT=y
|
||||
CONFIG_ESP_ROM_HAS_NEWLIB_32BIT_TIME=y
|
||||
CONFIG_ESP_ROM_HAS_SW_FLOAT=y
|
||||
CONFIG_ESP_ROM_USB_OTG_NUM=-1
|
||||
CONFIG_ESP_ROM_USB_SERIAL_DEVICE_NUM=-1
|
||||
CONFIG_ESP_ROM_SUPPORT_DEEP_SLEEP_WAKEUP_STUB=y
|
||||
|
||||
#
|
||||
# Serial flasher config
|
||||
@@ -373,6 +387,8 @@ CONFIG_PARTITION_TABLE_MD5=y
|
||||
#
|
||||
# DIY Power PCB Configuration
|
||||
#
|
||||
CONFIG_V2=y
|
||||
# CONFIG_V1 is not set
|
||||
CONFIG_ENV_GPIO_RANGE_MIN=0
|
||||
CONFIG_ENV_GPIO_RANGE_MAX=39
|
||||
CONFIG_ENV_GPIO_IN_RANGE_MAX=39
|
||||
@@ -391,18 +407,24 @@ CONFIG_TORQUE_ADC=4
|
||||
# Highside pin configurations (HIN)
|
||||
#
|
||||
CONFIG_HIN_U_V_W_GPIO="26, 14, 13"
|
||||
CONFIG_ENABLE_PWM_HIN=y
|
||||
CONFIG_FREQ_PWM_HIN=20000
|
||||
CONFIG_DUTY_PWM_HIN=50
|
||||
# end of Highside pin configurations (HIN)
|
||||
|
||||
#
|
||||
# Lowside pin configurations (LIN)
|
||||
#
|
||||
CONFIG_LIN_U_V_W_GPIO="25, 27, 12"
|
||||
# CONFIG_ENABLE_PWM_LIN is not set
|
||||
# end of Lowside pin configurations (LIN)
|
||||
|
||||
#
|
||||
# PWM configuration
|
||||
#
|
||||
CONFIG_ENABLE_PWM=y
|
||||
CONFIG_TIMER_BASE_FREQ=40000000
|
||||
CONFIG_FREQ_PWM=20000
|
||||
CONFIG_DUTY_PWM=50
|
||||
CONFIG_DEAD_TIME_PWM=0
|
||||
# end of PWM configuration
|
||||
|
||||
#
|
||||
# Hall Sensor pin configurations
|
||||
#
|
||||
@@ -412,13 +434,13 @@ CONFIG_HALL_A_B_C_GPIO="4, 16, 17"
|
||||
#
|
||||
# Input pin configurations
|
||||
#
|
||||
CONFIG_IN_ENCODER_GPIO="3, 2, 23"
|
||||
CONFIG_BUTTON_GPIO=1
|
||||
CONFIG_IN_ENCODER_GPIO="23,1,3"
|
||||
CONFIG_IN_ENCODER_GPIO_V2="23, 1, 3"
|
||||
CONFIG_IN_ENCODER_DEBOUNCE_TIME=500
|
||||
CONFIG_ESP_LED=2
|
||||
CONFIG_EXT_ENCODER_GPIO="16, 18, 5"
|
||||
CONFIG_RFE_GPIO=15
|
||||
# end of Input pin configurations
|
||||
|
||||
CONFIG_BLINK_PERIOD=1000
|
||||
# end of DIY Power PCB Configuration
|
||||
|
||||
#
|
||||
@@ -429,11 +451,11 @@ CONFIG_I2C_INTERFACE=y
|
||||
# CONFIG_SPI_INTERFACE is not set
|
||||
# CONFIG_SSD1306_128x32 is not set
|
||||
CONFIG_SSD1306_128x64=y
|
||||
CONFIG_OFFSETX=0
|
||||
CONFIG_OFFSETX=2
|
||||
# CONFIG_FLIP is not set
|
||||
CONFIG_SCL_GPIO=22
|
||||
CONFIG_SDA_GPIO=21
|
||||
CONFIG_RESET_GPIO=15
|
||||
CONFIG_RESET_GPIO=-1
|
||||
CONFIG_I2C_PORT_0=y
|
||||
# CONFIG_I2C_PORT_1 is not set
|
||||
# CONFIG_LEGACY_DRIVER is not set
|
||||
@@ -492,35 +514,16 @@ CONFIG_APPTRACE_LOCK_ENABLE=y
|
||||
CONFIG_BT_ALARM_MAX_NUM=50
|
||||
# end of Bluetooth
|
||||
|
||||
#
|
||||
# Console Library
|
||||
#
|
||||
# CONFIG_CONSOLE_SORTED_HELP is not set
|
||||
# end of Console Library
|
||||
|
||||
#
|
||||
# Driver Configurations
|
||||
#
|
||||
|
||||
#
|
||||
# Legacy ADC Configuration
|
||||
#
|
||||
CONFIG_ADC_DISABLE_DAC=y
|
||||
# CONFIG_ADC_SUPPRESS_DEPRECATE_WARN is not set
|
||||
|
||||
#
|
||||
# Legacy ADC Calibration Configuration
|
||||
#
|
||||
CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y
|
||||
CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y
|
||||
CONFIG_ADC_CAL_LUT_ENABLE=y
|
||||
# CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy ADC Calibration Configuration
|
||||
# end of Legacy ADC Configuration
|
||||
|
||||
#
|
||||
# SPI Configuration
|
||||
#
|
||||
# CONFIG_SPI_MASTER_IN_IRAM is not set
|
||||
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
|
||||
|
||||
#
|
||||
# TWAI Configuration
|
||||
#
|
||||
@@ -533,93 +536,62 @@ CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM=y
|
||||
# end of TWAI Configuration
|
||||
|
||||
#
|
||||
# UART Configuration
|
||||
# Legacy ADC Driver Configuration
|
||||
#
|
||||
# CONFIG_UART_ISR_IN_IRAM is not set
|
||||
# end of UART Configuration
|
||||
CONFIG_ADC_DISABLE_DAC=y
|
||||
# CONFIG_ADC_SUPPRESS_DEPRECATE_WARN is not set
|
||||
|
||||
#
|
||||
# GPIO Configuration
|
||||
# Legacy ADC Calibration Configuration
|
||||
#
|
||||
# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set
|
||||
# CONFIG_GPIO_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of GPIO Configuration
|
||||
CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y
|
||||
CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y
|
||||
CONFIG_ADC_CAL_LUT_ENABLE=y
|
||||
# CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy ADC Calibration Configuration
|
||||
# end of Legacy ADC Driver Configuration
|
||||
|
||||
#
|
||||
# Sigma Delta Modulator Configuration
|
||||
# Legacy DAC Driver Configurations
|
||||
#
|
||||
# CONFIG_SDM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_SDM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_SDM_ENABLE_DEBUG_LOG is not set
|
||||
# end of Sigma Delta Modulator Configuration
|
||||
|
||||
#
|
||||
# GPTimer Configuration
|
||||
#
|
||||
CONFIG_GPTIMER_ISR_HANDLER_IN_IRAM=y
|
||||
# CONFIG_GPTIMER_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_GPTIMER_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_GPTIMER_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_GPTIMER_ENABLE_DEBUG_LOG is not set
|
||||
# end of GPTimer Configuration
|
||||
|
||||
#
|
||||
# PCNT Configuration
|
||||
#
|
||||
# CONFIG_PCNT_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_PCNT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_PCNT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_PCNT_ENABLE_DEBUG_LOG is not set
|
||||
# end of PCNT Configuration
|
||||
|
||||
#
|
||||
# RMT Configuration
|
||||
#
|
||||
# CONFIG_RMT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_RMT_RECV_FUNC_IN_IRAM is not set
|
||||
# CONFIG_RMT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_RMT_ENABLE_DEBUG_LOG is not set
|
||||
# end of RMT Configuration
|
||||
|
||||
#
|
||||
# MCPWM Configuration
|
||||
#
|
||||
# CONFIG_MCPWM_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_MCPWM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_MCPWM_ENABLE_DEBUG_LOG is not set
|
||||
# end of MCPWM Configuration
|
||||
|
||||
#
|
||||
# I2S Configuration
|
||||
#
|
||||
# CONFIG_I2S_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2S_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_I2S_ENABLE_DEBUG_LOG is not set
|
||||
# end of I2S Configuration
|
||||
|
||||
#
|
||||
# DAC Configuration
|
||||
#
|
||||
# CONFIG_DAC_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_DAC_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_DAC_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# CONFIG_DAC_ENABLE_DEBUG_LOG is not set
|
||||
CONFIG_DAC_DMA_AUTO_16BIT_ALIGN=y
|
||||
# end of DAC Configuration
|
||||
# end of Legacy DAC Driver Configurations
|
||||
|
||||
#
|
||||
# LEDC Configuration
|
||||
# Legacy MCPWM Driver Configurations
|
||||
#
|
||||
# CONFIG_LEDC_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of LEDC Configuration
|
||||
# CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy MCPWM Driver Configurations
|
||||
|
||||
#
|
||||
# I2C Configuration
|
||||
# Legacy Timer Group Driver Configurations
|
||||
#
|
||||
# CONFIG_I2C_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2C_ENABLE_DEBUG_LOG is not set
|
||||
# end of I2C Configuration
|
||||
# CONFIG_GPTIMER_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy Timer Group Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy RMT Driver Configurations
|
||||
#
|
||||
# CONFIG_RMT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy RMT Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy I2S Driver Configurations
|
||||
#
|
||||
# CONFIG_I2S_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy I2S Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy PCNT Driver Configurations
|
||||
#
|
||||
# CONFIG_PCNT_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy PCNT Driver Configurations
|
||||
|
||||
#
|
||||
# Legacy SDM Driver Configurations
|
||||
#
|
||||
# CONFIG_SDM_SUPPRESS_DEPRECATE_WARN is not set
|
||||
# end of Legacy SDM Driver Configurations
|
||||
# end of Driver Configurations
|
||||
|
||||
#
|
||||
@@ -639,7 +611,9 @@ CONFIG_EFUSE_MAX_BLK_LEN=192
|
||||
CONFIG_ESP_TLS_USING_MBEDTLS=y
|
||||
# CONFIG_ESP_TLS_USE_SECURE_ELEMENT is not set
|
||||
# CONFIG_ESP_TLS_CLIENT_SESSION_TICKETS is not set
|
||||
# CONFIG_ESP_TLS_SERVER is not set
|
||||
# CONFIG_ESP_TLS_SERVER_SESSION_TICKETS is not set
|
||||
# CONFIG_ESP_TLS_SERVER_CERT_SELECT_HOOK is not set
|
||||
# CONFIG_ESP_TLS_SERVER_MIN_AUTH_MODE_OPTIONAL is not set
|
||||
# CONFIG_ESP_TLS_PSK_VERIFICATION is not set
|
||||
# CONFIG_ESP_TLS_INSECURE is not set
|
||||
# end of ESP-TLS
|
||||
@@ -659,11 +633,13 @@ CONFIG_ADC_CALI_LUT_ENABLE=y
|
||||
# end of ADC Calibration Configurations
|
||||
|
||||
CONFIG_ADC_DISABLE_DAC_OUTPUT=y
|
||||
# CONFIG_ADC_ENABLE_DEBUG_LOG is not set
|
||||
# end of ADC and ADC Calibration
|
||||
|
||||
#
|
||||
# Wireless Coexistence
|
||||
#
|
||||
CONFIG_ESP_COEX_ENABLED=y
|
||||
# end of Wireless Coexistence
|
||||
|
||||
#
|
||||
@@ -672,6 +648,97 @@ CONFIG_ADC_DISABLE_DAC_OUTPUT=y
|
||||
CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
||||
# end of Common ESP-related
|
||||
|
||||
#
|
||||
# ESP-Driver:DAC Configurations
|
||||
#
|
||||
# CONFIG_DAC_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_DAC_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_DAC_ENABLE_DEBUG_LOG is not set
|
||||
CONFIG_DAC_DMA_AUTO_16BIT_ALIGN=y
|
||||
# end of ESP-Driver:DAC Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:GPIO Configurations
|
||||
#
|
||||
# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set
|
||||
# CONFIG_GPIO_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of ESP-Driver:GPIO Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:GPTimer Configurations
|
||||
#
|
||||
CONFIG_GPTIMER_ISR_HANDLER_IN_IRAM=y
|
||||
# CONFIG_GPTIMER_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_GPTIMER_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_GPTIMER_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:GPTimer Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:I2C Configurations
|
||||
#
|
||||
# CONFIG_I2C_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2C_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:I2C Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:I2S Configurations
|
||||
#
|
||||
# CONFIG_I2S_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_I2S_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:I2S Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:LEDC Configurations
|
||||
#
|
||||
# CONFIG_LEDC_CTRL_FUNC_IN_IRAM is not set
|
||||
# end of ESP-Driver:LEDC Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:MCPWM Configurations
|
||||
#
|
||||
# CONFIG_MCPWM_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_MCPWM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_MCPWM_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:MCPWM Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:PCNT Configurations
|
||||
#
|
||||
# CONFIG_PCNT_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_PCNT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_PCNT_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:PCNT Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:RMT Configurations
|
||||
#
|
||||
# CONFIG_RMT_ISR_IRAM_SAFE is not set
|
||||
# CONFIG_RMT_RECV_FUNC_IN_IRAM is not set
|
||||
# CONFIG_RMT_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:RMT Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:Sigma Delta Modulator Configurations
|
||||
#
|
||||
# CONFIG_SDM_CTRL_FUNC_IN_IRAM is not set
|
||||
# CONFIG_SDM_ENABLE_DEBUG_LOG is not set
|
||||
# end of ESP-Driver:Sigma Delta Modulator Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:SPI Configurations
|
||||
#
|
||||
# CONFIG_SPI_MASTER_IN_IRAM is not set
|
||||
CONFIG_SPI_MASTER_ISR_IN_IRAM=y
|
||||
# CONFIG_SPI_SLAVE_IN_IRAM is not set
|
||||
CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||
# end of ESP-Driver:SPI Configurations
|
||||
|
||||
#
|
||||
# ESP-Driver:UART Configurations
|
||||
#
|
||||
# CONFIG_UART_ISR_IN_IRAM is not set
|
||||
# end of ESP-Driver:UART Configurations
|
||||
|
||||
#
|
||||
# Ethernet
|
||||
#
|
||||
@@ -716,6 +783,7 @@ CONFIG_ESP_GDBSTUB_MAX_TASKS=32
|
||||
CONFIG_ESP_HTTP_CLIENT_ENABLE_HTTPS=y
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_BASIC_AUTH is not set
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_DIGEST_AUTH is not set
|
||||
# CONFIG_ESP_HTTP_CLIENT_ENABLE_CUSTOM_TRANSPORT is not set
|
||||
# end of ESP HTTP client
|
||||
|
||||
#
|
||||
@@ -765,12 +833,6 @@ CONFIG_ESP_REV_MIN_FULL=0
|
||||
#
|
||||
CONFIG_ESP32_REV_MAX_FULL=399
|
||||
CONFIG_ESP_REV_MAX_FULL=399
|
||||
CONFIG_ESP_EFUSE_BLOCK_REV_MIN_FULL=0
|
||||
CONFIG_ESP_EFUSE_BLOCK_REV_MAX_FULL=99
|
||||
|
||||
#
|
||||
# Maximum Supported ESP32 eFuse Block Revision (eFuse Block Rev v0.99)
|
||||
#
|
||||
# end of Chip revision
|
||||
|
||||
#
|
||||
@@ -781,6 +843,7 @@ CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y
|
||||
CONFIG_ESP_MAC_UNIVERSAL_MAC_ADDRESSES_FOUR=y
|
||||
CONFIG_ESP_MAC_UNIVERSAL_MAC_ADDRESSES=4
|
||||
# CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO is not set
|
||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR=y
|
||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4
|
||||
@@ -826,6 +889,8 @@ CONFIG_XTAL_FREQ_40=y
|
||||
# CONFIG_XTAL_FREQ_AUTO is not set
|
||||
CONFIG_XTAL_FREQ=40
|
||||
# end of Main XTAL Config
|
||||
|
||||
CONFIG_ESP_SPI_BUS_LOCK_ISR_FUNCS_IN_IRAM=y
|
||||
# end of Hardware Settings
|
||||
|
||||
#
|
||||
@@ -854,7 +919,6 @@ CONFIG_ESP_NETIF_USES_TCPIP_WITH_BSD_API=y
|
||||
# CONFIG_ESP_NETIF_RECEIVE_REPORT_ERRORS is not set
|
||||
# CONFIG_ESP_NETIF_L2_TAP is not set
|
||||
# CONFIG_ESP_NETIF_BRIDGE_EN is not set
|
||||
# CONFIG_ESP_NETIF_SET_DNS_PER_DEFAULT_NETIF is not set
|
||||
# end of ESP NETIF Adapter
|
||||
|
||||
#
|
||||
@@ -865,6 +929,7 @@ CONFIG_ESP_NETIF_USES_TCPIP_WITH_BSD_API=y
|
||||
#
|
||||
# PHY
|
||||
#
|
||||
CONFIG_ESP_PHY_ENABLED=y
|
||||
CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y
|
||||
# CONFIG_ESP_PHY_INIT_DATA_IN_PARTITION is not set
|
||||
CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20
|
||||
@@ -946,6 +1011,7 @@ CONFIG_ESP_CONSOLE_UART_DEFAULT=y
|
||||
# CONFIG_ESP_CONSOLE_NONE is not set
|
||||
CONFIG_ESP_CONSOLE_UART=y
|
||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||
CONFIG_ESP_CONSOLE_ROM_SERIAL_PORT_NUM=0
|
||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||
CONFIG_ESP_INT_WDT=y
|
||||
CONFIG_ESP_INT_WDT_TIMEOUT_MS=300
|
||||
@@ -990,7 +1056,7 @@ CONFIG_ESP_IPC_ISR_ENABLE=y
|
||||
# end of IPC (Inter-Processor Call)
|
||||
|
||||
#
|
||||
# High resolution timer (esp_timer)
|
||||
# ESP Timer (High Resolution Timer)
|
||||
#
|
||||
# CONFIG_ESP_TIMER_PROFILING is not set
|
||||
CONFIG_ESP_TIME_FUNCS_USE_RTC_TIMER=y
|
||||
@@ -1000,11 +1066,10 @@ CONFIG_ESP_TIMER_INTERRUPT_LEVEL=1
|
||||
# CONFIG_ESP_TIMER_SHOW_EXPERIMENTAL is not set
|
||||
CONFIG_ESP_TIMER_TASK_AFFINITY=0x0
|
||||
CONFIG_ESP_TIMER_TASK_AFFINITY_CPU0=y
|
||||
CONFIG_ESP_TIMER_ISR_AFFINITY=0x1
|
||||
CONFIG_ESP_TIMER_ISR_AFFINITY_CPU0=y
|
||||
# CONFIG_ESP_TIMER_SUPPORTS_ISR_DISPATCH_METHOD is not set
|
||||
CONFIG_ESP_TIMER_IMPL_TG0_LAC=y
|
||||
# end of High resolution timer (esp_timer)
|
||||
# end of ESP Timer (High Resolution Timer)
|
||||
|
||||
#
|
||||
# Wi-Fi
|
||||
@@ -1115,6 +1180,8 @@ CONFIG_FATFS_PER_FILE_CACHE=y
|
||||
# CONFIG_FATFS_USE_FASTSEEK is not set
|
||||
CONFIG_FATFS_VFS_FSTAT_BLKSIZE=0
|
||||
# CONFIG_FATFS_IMMEDIATE_FSYNC is not set
|
||||
# CONFIG_FATFS_USE_LABEL is not set
|
||||
CONFIG_FATFS_LINK_LOCK=y
|
||||
# end of FAT Filesystem support
|
||||
|
||||
#
|
||||
@@ -1136,14 +1203,18 @@ CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536
|
||||
# CONFIG_FREERTOS_USE_TICK_HOOK is not set
|
||||
CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16
|
||||
# CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY is not set
|
||||
CONFIG_FREERTOS_USE_TIMERS=y
|
||||
CONFIG_FREERTOS_TIMER_SERVICE_TASK_NAME="Tmr Svc"
|
||||
# CONFIG_FREERTOS_TIMER_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_FREERTOS_TIMER_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_FREERTOS_TIMER_TASK_NO_AFFINITY=y
|
||||
CONFIG_FREERTOS_TIMER_SERVICE_TASK_CORE_AFFINITY=0x7FFFFFFF
|
||||
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_TASK_NOTIFICATION_ARRAY_ENTRIES=1
|
||||
# CONFIG_FREERTOS_USE_TRACE_FACILITY is not set
|
||||
# CONFIG_FREERTOS_USE_LIST_DATA_INTEGRITY_CHECK_BYTES is not set
|
||||
# CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS is not set
|
||||
# CONFIG_FREERTOS_USE_APPLICATION_TASK_TAG is not set
|
||||
# end of Kernel
|
||||
@@ -1174,6 +1245,7 @@ CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y
|
||||
CONFIG_FREERTOS_DEBUG_OCDAWARE=y
|
||||
CONFIG_FREERTOS_ENABLE_TASK_SNAPSHOT=y
|
||||
CONFIG_FREERTOS_PLACE_SNAPSHOT_FUNS_INTO_FLASH=y
|
||||
CONFIG_FREERTOS_NUMBER_OF_CORES=2
|
||||
# end of FreeRTOS
|
||||
|
||||
#
|
||||
@@ -1301,6 +1373,7 @@ CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000
|
||||
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5760
|
||||
CONFIG_LWIP_TCP_WND_DEFAULT=5760
|
||||
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
||||
CONFIG_LWIP_TCP_ACCEPTMBOX_SIZE=6
|
||||
CONFIG_LWIP_TCP_QUEUE_OOSEQ=y
|
||||
CONFIG_LWIP_TCP_OOSEQ_TIMEOUT=6
|
||||
CONFIG_LWIP_TCP_OOSEQ_MAX_PBUFS=4
|
||||
@@ -1331,9 +1404,6 @@ CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_PREFIXES=5
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_ROUTERS=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_DESTINATIONS=10
|
||||
# CONFIG_LWIP_PPP_SUPPORT is not set
|
||||
CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5
|
||||
@@ -1359,15 +1429,15 @@ CONFIG_LWIP_MAX_RAW_PCBS=16
|
||||
CONFIG_LWIP_SNTP_MAX_SERVERS=1
|
||||
# CONFIG_LWIP_DHCP_GET_NTP_SRV is not set
|
||||
CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000
|
||||
CONFIG_LWIP_SNTP_STARTUP_DELAY=y
|
||||
CONFIG_LWIP_SNTP_MAXIMUM_STARTUP_DELAY=5000
|
||||
# end of SNTP
|
||||
|
||||
#
|
||||
# DNS
|
||||
#
|
||||
CONFIG_LWIP_DNS_MAX_HOST_IP=1
|
||||
CONFIG_LWIP_DNS_MAX_SERVERS=3
|
||||
# CONFIG_LWIP_FALLBACK_DNS_SERVER_SUPPORT is not set
|
||||
# CONFIG_LWIP_DNS_SETSERVER_WITH_NETIF is not set
|
||||
# end of DNS
|
||||
|
||||
CONFIG_LWIP_BRIDGEIF_MAX_PORTS=7
|
||||
@@ -1430,13 +1500,14 @@ 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
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEPRECATED_LIST is not set
|
||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200
|
||||
# end of Certificate Bundle
|
||||
|
||||
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
||||
CONFIG_MBEDTLS_CMAC_C=y
|
||||
CONFIG_MBEDTLS_HARDWARE_AES=y
|
||||
# CONFIG_MBEDTLS_GCM_SUPPORT_NON_AES_CIPHER is not set
|
||||
CONFIG_MBEDTLS_GCM_SUPPORT_NON_AES_CIPHER=y
|
||||
CONFIG_MBEDTLS_HARDWARE_MPI=y
|
||||
# CONFIG_MBEDTLS_LARGE_KEY_SOFTWARE_MPI is not set
|
||||
CONFIG_MBEDTLS_HARDWARE_SHA=y
|
||||
@@ -1639,6 +1710,7 @@ CONFIG_SPI_FLASH_BROWNOUT_RESET=y
|
||||
#
|
||||
# Features here require specific hardware (READ DOCS FIRST!)
|
||||
#
|
||||
CONFIG_SPI_FLASH_SUSPEND_TSUS_VAL_US=50
|
||||
# end of Optional and Experimental Features (READ DOCS FIRST)
|
||||
# end of Main Flash configuration
|
||||
|
||||
@@ -1733,6 +1805,11 @@ CONFIG_WS_BUFFER_SIZE=1024
|
||||
# Ultra Low Power (ULP) Co-processor
|
||||
#
|
||||
# CONFIG_ULP_COPROC_ENABLED is not set
|
||||
|
||||
#
|
||||
# ULP Debugging Options
|
||||
#
|
||||
# end of ULP Debugging Options
|
||||
# end of Ultra Low Power (ULP) Co-processor
|
||||
|
||||
#
|
||||
|
||||
Reference in New Issue
Block a user