sdk5.12 build

This commit is contained in:
Holy 2024-02-19 09:58:15 +08:00
parent 905f936721
commit f305cb1a2e
16 changed files with 3109 additions and 582 deletions

View File

@ -12,7 +12,7 @@
#include "esp_check.h"
#define MOTOR_CTRL_TIMER_DIVIDER (16) // Hardware timer clock divider
#define MOTOR_CTRL_TIMER_SCALE (TIMER_BASE_CLK / MOTOR_CTRL_TIMER_DIVIDER) // convert counter value to seconds
#define MOTOR_CTRL_TIMER_SCALE (TIMER_SRC_CLK_APB / MOTOR_CTRL_TIMER_DIVIDER) // convert counter value to seconds
#define MOTOR_CONTROL_TIMER_GROUP TIMER_GROUP_0
#define MOTOR_CONTROL_TIMER_ID TIMER_0

View File

@ -59,10 +59,10 @@ static uint16_t spp_mtu_size = 23;
uint16_t spp_conn_id = 0xffff;
esp_gatt_if_t spp_gatts_if = 0xff;
QueueHandle_t spp_uart_queue = NULL;
static xQueueHandle cmd_cmd_queue = NULL;
static QueueHandle_t cmd_cmd_queue = NULL;
#ifdef SUPPORT_HEARTBEAT
static xQueueHandle cmd_heartbeat_queue = NULL;
static QueueHandle_t cmd_heartbeat_queue = NULL;
static uint8_t heartbeat_s[9] = {'E','s','p','r','e','s','s','i','f'};
static bool enable_heart_ntf = false;
static uint8_t heartbeat_count_num = 0;

View File

@ -101,7 +101,7 @@ static void twai_receive_task(void *arg)
{
index += sprintf(&msg_data_str[i], "%02x ", rx_msg.data[i]);
}
ESP_LOGI(TAG, "recive msg id=%x,len=%d,data=[%s]", rx_msg.identifier, rx_msg.data_length_code, msg_data_str);
ESP_LOGI(TAG, "recive msg id=%lx,len=%u,data=[%s]", rx_msg.identifier, rx_msg.data_length_code, msg_data_str);
}
}
}

View File

@ -25,15 +25,15 @@
#include "esp_check.h"
#include "soc/rtc.h"
#include "driver/mcpwm.h"
#include "driver/uart.h"
/*蓝牙相关的头文件*/
#include "esp_bt.h"
#include "driver/uart.h"
#include "esp_gap_ble_api.h"
#include "esp_gatts_api.h"
#include "esp_bt_defs.h"
#include "esp_bt_main.h"
/* The examples use WiFi configuration that you can set via project configuration menu
If you'd rather not, just change the below entries to strings with
@ -105,8 +105,8 @@ void app_main(void)
ESP_ERROR_CHECK(i2c_master_init());
config_load();
ESP_LOGI(TAG, "ESP_WIFI_MODE_STA");
rtc_clk_apb_freq = rtc_clk_apb_freq_get();
ESP_LOGI(TAG, "rtc_clk_apb_freq=%d", rtc_clk_apb_freq);
// rtc_clk_apb_freq = rtc_clk_apb_freq_get();
// ESP_LOGI(TAG, "rtc_clk_apb_freq=%u", rtc_clk_apb_freq);
wifi_init_softap();//ok
// wifi_init_sta();

1960
main/sdkconfig Normal file

File diff suppressed because it is too large Load Diff

View File

@ -92,10 +92,10 @@ static spi_device_handle_t spi2;
#define ESP_INTR_FLAG_DEFAULT 0
int ads1220_watchdog = 0;
extern xQueueHandle gpio_evt_queue;
extern QueueHandle_t gpio_evt_queue;
xQueueHandle gpio_evt_queue = NULL;
uint16_t gWordVar[gWORD_SIZE];
QueueHandle_t gpio_evt_queue = NULL;
// uint16_t gWordVar[gWORD_SIZE];
int ad_value[4];
uint32_t ad_update_time[4];
uint8_t ad_watchdog_cnt = 0;

View File

@ -25,9 +25,7 @@
extern move_t *pMoveCtx;
// To speed up transfers, every SPI transfer sends a bunch of lines. This define specifies how many. More means more memory use,
// but less overhead for setting up / finishing transfers. Make sure 240 is dividable by this.
#define PARALLEL_LINES 16
static spi_device_handle_t spi1;
static void SPI1_Init(void)
@ -40,15 +38,11 @@ static void SPI1_Init(void)
.sclk_io_num = SPI1_PIN_NUM_CLK,
.quadwp_io_num = -1,
.quadhd_io_num = -1,
.max_transfer_sz = PARALLEL_LINES * 320 * 2 + 8};
.max_transfer_sz = 128
};
spi_device_interface_config_t devcfg1 = {
#ifdef CONFIG_LCD_OVERCLOCK
.clock_speed_hz = 26 * 1000 * 1000, // Clock out at 26 MHz
#else
.clock_speed_hz = 8 * 100 * 1000, // Clock out at 800kHz
#endif
.mode = 1, // SPI mode 1
.spics_io_num = SPI1_PIN_NUM_CS, // CS pin
.queue_size = 7, // We want to be able to queue 7 transactions at a time

View File

@ -9,6 +9,7 @@
#include "esp_check.h"
#include "soc/rtc.h"
#include "driver/mcpwm.h"
#include "driver/gpio.h"
const static char *TAG = "capture";

View File

@ -29,7 +29,6 @@
#include <string.h>
#include <stdio.h>
static const char *TAG = "depth";
typedef struct
@ -50,13 +49,13 @@ typedef struct capture_event
// #define DEPTH_PIN_PULSE 36 //深度脉冲GPIO端口
// #define DEPTH_PIN_CTRL 35 //深度控制GPIO端口
#define FLOW_SYNC_PIN 7 // 捕获GPIO端口 SPI2_nIRQ
#define FLOW_SYNC_PIN 7 // 捕获GPIO端口 SPI2_nIRQ
#define DEPTH_PIN_PULSE 39 // 深度脉冲GPIO端口 TIM15_CH1
#define DEPTH_PIN_CTRL 38 // 深度控制GPIO端口 TIM15_CH2
#define DEPTH_PIN_PULSE 39 // 深度脉冲GPIO端口 TIM15_CH1
#define DEPTH_PIN_CTRL 38 // 深度控制GPIO端口 TIM15_CH2
#define DEPTH_PIN_ENC_A 42 // 深度脉冲GPIO端口 TIM3_CH1
#define DEPTH_PIN_ENC_B 41 // 深度控制GPIO端口 TIM3_CH2
#define SEND_DATA_TEST 0
#define SEND_DATA_TEST 0
// #define DEPTH_PIN_ENC_A 36 // 深度脉冲GPIO端口
// #define DEPTH_PIN_ENC_B 35 // 深度控制GPIO端口
@ -87,7 +86,7 @@ typedef struct
int16_t max_depth;
uint16_t pile_id;
uint16_t count;
//uint16_t work_time;
// uint16_t work_time;
struct _item
{
int16_t speed;
@ -101,25 +100,61 @@ typedef struct
} item[10];
} record_t;
//18字节
#pragma pack(1)
typedef struct {
// 18字节
#pragma pack(1)
typedef struct
{
uint8_t TAG;
int16_t speed;
int16_t depth;
int16_t tilt_x;
int16_t tilt_y;
uint16_t current1;
uint16_t current2;
}send_to_bt_t1;
//16字节
typedef struct{
uint8_t TAG;
int16_t flow[2];
uint32_t total_flow[2];
}send_to_bt_t2;
#pragma pack()
uint16_t current1;
uint16_t current2;
} send_to_bt_t1;
// 16字节
typedef struct
{
uint8_t TAG;
uint8_t status;
uint8_t LAT[5];
uint8_t LOG[5];
int16_t ALT; // 海拔高度
int16_t speed;
uint32_t UTC;
// uint16_t dir;
// uint16_t speed;
// int16_t tilt_x;
// int16_t tilt_y;
} position_t;
typedef struct
{
uint8_t TAG;
int16_t distence;
int16_t pitch;
int16_t azimuth;
int16_t tilt_x;
int16_t tilt_y;
}direction_t;
typedef struct
{
uint8_t TAG;
uint8_t status;
uint8_t LAT[5];
uint8_t LOG[5];
int16_t ALT; // 海拔高度
int16_t speed;
uint32_t UTC;
// uint16_t dir;
// uint16_t speed;
// int16_t tilt_x;
// int16_t tilt_y;
} send_to_bt_t2;
#pragma pack()
typedef struct
{
@ -138,18 +173,16 @@ typedef struct
// uint16_t current3;
} depth_t;
record_t *record = (record_t *)&gWordVar[RECORD_REG_ADDR];
depth_t *depth_data = (depth_t *)&gWordVar[DEPTH_REG_ADDR];
move_t *pMoveCtx = (move_t *)&gWordVar[MOVE_REG_ADDR];
depth_config_t *depth_config = (depth_config_t *)&gWordVar[DEPTH_CONFIG_ADDR];
rotary_encoder_t *encoder = NULL; // 编码器测量深度参数
//static uint32_t cap_val_begin_of_depth = 0;
//static uint32_t cap_val_end_of_depth = 0;
//extern uint32_t rtc_clk_apb_freq;
// static uint32_t cap_val_begin_of_depth = 0;
// static uint32_t cap_val_end_of_depth = 0;
// extern uint32_t rtc_clk_apb_freq;
/**
* @brief this is an ISR callback, we take action according to the captured edge
*/
@ -286,82 +319,89 @@ int abs_sub(uint32_t enc_update_time, uint32_t _enc_update_time)
}
}
send_to_bt_t1 send_to_bt1;
send_to_bt_t2 send_to_bt2;
extern bool is_connected;
extern uint16_t spp_handle_table[SPP_IDX_NB];
extern uint16_t spp_conn_id;
extern esp_gatt_if_t spp_gatts_if;
extern flow_t *pflow ;
extern flow_t *pflow;
/*把两个结构体中的数据通过蓝牙发送*/
void send_data_to_bt(void){
void send_data_to_bt(void)
{
#if SEND_DATA_TEST
send_to_bt1.TAG = 1;
send_to_bt1.speed = 2;
send_to_bt1.depth = 3;
send_to_bt1.tilt_x = 4;
send_to_bt1.tilt_y = 5;
send_to_bt1.current1 = 6;
send_to_bt1.current2 = 7;
// #if SEND_DATA_TEST
// send_to_bt1.TAG = 1;
// send_to_bt1.speed = 2;
// send_to_bt1.depth = 3;
// send_to_bt1.tilt_x = 4;
// send_to_bt1.tilt_y = 5;
// send_to_bt1.current1 = 6;
// send_to_bt1.current2 = 7;
send_to_bt2.TAG = 2;
send_to_bt2.flow[0] = 3;
send_to_bt2.flow[1] = 4;
send_to_bt2.total_flow[0] = 5;
send_to_bt2.total_flow[1] = 6;
ESP_LOGI(TAG, "set text data that send to bt\n");
#else
ESP_LOGI(TAG, "use real time data that send to bt\n");
send_to_bt1.TAG = 1;
send_to_bt1.tilt_x = (short)gWordVar[TILT_SENSER_ADDR];
send_to_bt1.tilt_y = (short)gWordVar[TILT_SENSER_ADDR + 1];
send_to_bt1.speed = depth_data->speed;
send_to_bt1.depth = depth_data->depth;
if (depth_config->move_current_channel == 2){
send_to_bt1.current1 = gWordVar[AC_CURRENT_REG_ADDR];
send_to_bt1.current2 = gWordVar[AC_CURRENT_REG_ADDR + 1];
}
else if (depth_config->move_current_channel == 1){
send_to_bt1.current1 = gWordVar[AC_CURRENT_REG_ADDR];
send_to_bt1.current2 = gWordVar[AC_CURRENT_REG_ADDR + 2];
}
else{
send_to_bt1.current1 = gWordVar[AC_CURRENT_REG_ADDR + 1];
send_to_bt1.current2 = gWordVar[AC_CURRENT_REG_ADDR + 2];
}
send_to_bt2.TAG = 2;
send_to_bt2.flow[0] = pflow[0].flow;
send_to_bt2.flow[1] = pflow[1].flow;
send_to_bt2.total_flow[0] = pflow[0].total_flow;
send_to_bt2.total_flow[1] = pflow[1].total_flow;
#endif
ESP_LOGI(TAG, "flow 1 :%d\n",send_to_bt2.flow[0]);
ESP_LOGI(TAG, "flow 2 :%d\n",send_to_bt2.flow[1]);
ESP_LOGI(TAG, "total_flow 1 :%d\n",send_to_bt2.total_flow[0]);
ESP_LOGI(TAG, "total_flow 2 :%d\n",send_to_bt2.total_flow[1]);
if(is_connected == true){
ESP_LOGI(TAG, "is connected\n");
esp_err_t err = esp_ble_gatts_send_indicate(spp_gatts_if,
spp_conn_id,
spp_handle_table[4],
sizeof(send_to_bt1),
(uint8*)&send_to_bt1,
false);
if(err == ESP_OK) ESP_LOGI(TAG, "send data to bt 1 sucessfully\n");
else ESP_LOGI(TAG, "send data to bt 1 failed\n");
// send_to_bt2.TAG = 2;
// send_to_bt2.flow[0] = 3;
// send_to_bt2.flow[1] = 4;
// send_to_bt2.total_flow[0] = 5;
// send_to_bt2.total_flow[1] = 6;
// ESP_LOGI(TAG, "set text data that send to bt\n");
// #else
// ESP_LOGI(TAG, "use real time data that send to bt\n");
// send_to_bt1.TAG = 1;
// send_to_bt1.tilt_x = (short)gWordVar[TILT_SENSER_ADDR];
// send_to_bt1.tilt_y = (short)gWordVar[TILT_SENSER_ADDR + 1];
// send_to_bt1.speed = depth_data->speed;
// send_to_bt1.depth = depth_data->depth;
// if (depth_config->move_current_channel == 2)
// {
// send_to_bt1.current1 = gWordVar[AC_CURRENT_REG_ADDR];
// send_to_bt1.current2 = gWordVar[AC_CURRENT_REG_ADDR + 1];
// }
// else if (depth_config->move_current_channel == 1)
// {
// send_to_bt1.current1 = gWordVar[AC_CURRENT_REG_ADDR];
// send_to_bt1.current2 = gWordVar[AC_CURRENT_REG_ADDR + 2];
// }
// else
// {
// send_to_bt1.current1 = gWordVar[AC_CURRENT_REG_ADDR + 1];
// send_to_bt1.current2 = gWordVar[AC_CURRENT_REG_ADDR + 2];
// }
// send_to_bt2.TAG = 2;
// send_to_bt2.flow[0] = pflow[0].flow;
// send_to_bt2.flow[1] = pflow[1].flow;
// send_to_bt2.total_flow[0] = pflow[0].total_flow;
// send_to_bt2.total_flow[1] = pflow[1].total_flow;
// #endif
// ESP_LOGI(TAG, "flow 1 :%d\n", send_to_bt2.flow[0]);
// ESP_LOGI(TAG, "flow 2 :%d\n", send_to_bt2.flow[1]);
// ESP_LOGI(TAG, "total_flow 1 :%d\n", send_to_bt2.total_flow[0]);
// ESP_LOGI(TAG, "total_flow 2 :%d\n", send_to_bt2.total_flow[1]);
// if (is_connected == true)
// {
// ESP_LOGI(TAG, "is connected\n");
// esp_err_t err = esp_ble_gatts_send_indicate(spp_gatts_if,
// spp_conn_id,
// spp_handle_table[4],
// sizeof(send_to_bt1),
// (uint8 *)&send_to_bt1,
// false);
// if (err == ESP_OK)
// ESP_LOGI(TAG, "send data to bt 1 sucessfully\n");
// else
// ESP_LOGI(TAG, "send data to bt 1 failed\n");
err = esp_ble_gatts_send_indicate(spp_gatts_if,
spp_conn_id,
spp_handle_table[4],
sizeof(send_to_bt2),
(uint8*)&send_to_bt2,
false);
if(err == ESP_OK) ESP_LOGI(TAG, "send data to bt 2 sucessfully\n");
else ESP_LOGI(TAG, "send data to bt 2 failed\n");
}
// err = esp_ble_gatts_send_indicate(spp_gatts_if,
// spp_conn_id,
// spp_handle_table[4],
// sizeof(send_to_bt2),
// (uint8 *)&send_to_bt2,
// false);
// if (err == ESP_OK)
// ESP_LOGI(TAG, "send data to bt 2 sucessfully\n");
// else
// ESP_LOGI(TAG, "send data to bt 2 failed\n");
// }
}
void depth_task(void *arg)
@ -374,18 +414,18 @@ void depth_task(void *arg)
int speed_enc_update_time = 0; // 上次速度计算的编码器值
int speed_calc_count = 0;
int enc_value = 0;
//int count = 0;
// int count = 0;
int bt_time_count = 0;
depth_data->depth_offset = -depth_config->depth_offset;
depth_data->up_down = 1; // 默认工作
record->pile_id = ++last_pile_id;
//send_to_bt1.pile_id = ++last_pile_id;
// send_to_bt1.pile_id = ++last_pile_id;
gWordVar[LAST_PILE_ID_ADDR] = last_pile_id;
while (1)
{
{
if (_enc1_update_time != enc1_update_time)
{
ESP_LOGI(TAG, "_enc1_update_time != enc1_update_time\n");
@ -395,7 +435,7 @@ void depth_task(void *arg)
time_diff = abs_sub(enc_update_time, _enc1_update_time);
_enc1_update_time = enc_update_time;
}
if (time_diff != 0)
{
ESP_LOGI(TAG, "time_diff != 0\n");
@ -417,7 +457,7 @@ void depth_task(void *arg)
{
ESP_LOGI(TAG, "depth_data->depth > record->max_depth\n");
record->max_depth = depth_data->depth;
//send_to_bt1.max_depth = depth_data->depth;
// send_to_bt1.max_depth = depth_data->depth;
}
if (speed_calc_count++ > 50) // 500ms计算一次速度
{
@ -466,7 +506,7 @@ void depth_task(void *arg)
if ((prev_depth - depth_data->depth) != 0)
{
int i;
//uint32_t time = (target_sample_depth - prev_depth) * (enc_update_time - prev_update_time) / (depth_data->depth - prev_depth) + prev_update_time;
// uint32_t time = (target_sample_depth - prev_depth) * (enc_update_time - prev_update_time) / (depth_data->depth - prev_depth) + prev_update_time;
for (i = 0; i < 2; i++)
{
// int total_flow = get_total_flow_by_time(i, time);
@ -504,7 +544,7 @@ void depth_task(void *arg)
if ((prev_depth - depth_data->depth) != 0)
{
int i;
//uint32_t time = (prev_depth - target_sample_depth) * (enc_update_time - prev_update_time) / (prev_depth - depth_data->depth) + prev_update_time;
// uint32_t time = (prev_depth - target_sample_depth) * (enc_update_time - prev_update_time) / (prev_depth - depth_data->depth) + prev_update_time;
for (i = 0; i < 2; i++)
{
// int total_flow = get_total_flow_by_time(i, time);
@ -520,7 +560,6 @@ void depth_task(void *arg)
depth_data->sample_count++;
add_recod_item();
target_sample_depth -= depth_config->sample_depth;
}
}
}
@ -549,14 +588,15 @@ void depth_task(void *arg)
prev_update_time = enc_update_time;
last_enc_value = enc_value;
}
////////////////////////////////////////////////////////////////////
//每隔500ms向蓝牙发送一次数据
if(bt_time_count++ > 50){
ESP_LOGI(TAG, "bt_time_count++ > 50\n");
bt_time_count = 0;
send_data_to_bt();
}
////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////
// 每隔500ms向蓝牙发送一次数据
if (bt_time_count++ > 50)
{
ESP_LOGI(TAG, "bt_time_count++ > 50\n");
bt_time_count = 0;
send_data_to_bt();
}
////////////////////////////////////////////////////////////////////
// if (++count > 100)
// {
// count = 0;
@ -568,8 +608,8 @@ void depth_task(void *arg)
void add_recod_item(void)
{
//每10cm计算一次
record->count = depth_data->sample_count;
// 每10cm计算一次
record->count = depth_data->sample_count;
memmove(&record->item[1], &record->item[0], sizeof(record->item[0]) * 9);
record->item[0].flow[0] = depth_data->depth_flow[0];
record->item[0].flow[1] = depth_data->depth_flow[1];
@ -595,14 +635,14 @@ void add_recod_item(void)
record->item[0].tilt_x = (short)gWordVar[TILT_SENSER_ADDR];
record->item[0].tilt_y = (short)gWordVar[TILT_SENSER_ADDR + 1];
record->item[0].speed = depth_data->speed; //每500ms计算一次
record->item[0].depth = depth_data->depth; //每10ms计算一次
record->item[0].speed = depth_data->speed; // 每500ms计算一次
record->item[0].depth = depth_data->depth; // 每10ms计算一次
}
extern int zero_totalflow_req;
extern void save_pile_id(void);
void reset_depth(void)
{
//uint16_t pile_id;
// uint16_t pile_id;
last_sample_depth = 0;
last_flow[0] = 0;
last_flow[1] = 0;
@ -624,7 +664,7 @@ void reset_depth(void)
}
memset(record, 0, sizeof(*record));
record->pile_id = last_pile_id;
//ec11_pcnt_clear(0);
// ec11_pcnt_clear(0);
depth_data->depth_offset = -depth_config->depth_offset;
depth_data->depth = depth_config->depth_offset;
enc1_value = 0;
@ -641,5 +681,3 @@ void DEPTH_init()
capture_depth_init();
xTaskCreate(depth_task, "depth_task", 4096, NULL, 10, NULL);
}

View File

@ -200,8 +200,8 @@ void flow_task(void *arg)
ccr = ccr / (rtc_clk_apb_freq / 1000000);
// __enable_irq();
time_diff = ccr - last_ccr[ch];
ESP_LOGI(TAG, "(type2) t15_ccr_times[%d]: %u %u time_diff: %u", ch, ccr, ccr_times, time_diff);
printf("rtc_clk_apb_freq : %u\n", rtc_clk_apb_freq);
ESP_LOGI(TAG, "(type2) t15_ccr_times[%d]: %lu %d time_diff: %d", ch, ccr, ccr_times, time_diff);
ESP_LOGI(TAG,"rtc_clk_apb_freq : %lu\n", rtc_clk_apb_freq);
if (time_diff != 0)
{
int t_flow;

View File

@ -8,6 +8,7 @@
#include "freertos/task.h"
#include "esp_system.h"
#include "sdkconfig.h"
#include "driver/gpio.h"
static const char *TAG = "i2c-simple-example";
@ -86,7 +87,7 @@ int fram_write(uint16_t addr, void * buf,uint32_t len)
i2c_master_write(cmd, &low_addr, 1, ACK_CHECK_EN);
i2c_master_write(cmd, buf, len, ACK_CHECK_EN);
i2c_master_stop(cmd);
ret = i2c_master_cmd_begin(I2C_MASTER_NUM, cmd, 1000 / portTICK_RATE_MS);
ret = i2c_master_cmd_begin(I2C_MASTER_NUM, cmd, 1000 / portTICK_PERIOD_MS);
if (ret != ESP_OK) {
printf("esp_err : %s \n", esp_err_to_name(ret));
return ret;

View File

@ -20,7 +20,7 @@ static const char *TAG = "UART0";
#define BAUD_RATE (115200)
#define UART_PORT_NUM (0)
#define BUF_SIZE (256)
#define UART_READ_TOUT (50 / portTICK_RATE_MS)
#define UART_READ_TOUT (50 / portTICK_PERIOD_MS)
#define LED1_GPIO_PIN 9

View File

@ -40,9 +40,9 @@ int GetCompileDateTime(uint16_t *DateTime)
return 0;
}
unsigned int TickDiff(unsigned int comptime)
uint32_t TickDiff(uint32_t comptime)
{
unsigned int nowtime = xTaskGetTickCount();
uint32_t nowtime = xTaskGetTickCount();
if(nowtime >= comptime)
return (nowtime - comptime);
else

View File

@ -2,5 +2,5 @@
#ifndef _UTILS_H_
#define _UTILS_H_
int GetCompileDateTime(uint16_t *DateTime);
extern unsigned int TickDiff(unsigned int comptime);
extern uint32_t TickDiff(uint32_t comptime);
#endif

View File

@ -45,20 +45,17 @@ static const char *TAG = "wifi softAP";
static void wifi_event_handler(void *arg, esp_event_base_t event_base,
int32_t event_id, void *event_data)
{
if (event_id == WIFI_EVENT_AP_STACONNECTED)
{
wifi_event_ap_staconnected_t *event = (wifi_event_ap_staconnected_t *)event_data;
ESP_LOGI(TAG, "station " MACSTR " join, AID=%d",
MAC2STR(event->mac), event->aid);
}
else if (event_id == WIFI_EVENT_AP_STADISCONNECTED)
{
wifi_event_ap_stadisconnected_t *event = (wifi_event_ap_stadisconnected_t *)event_data;
ESP_LOGI(TAG, "station " MACSTR " leave, AID=%d",
MAC2STR(event->mac), event->aid);
}
// if (event_id == WIFI_EVENT_AP_STACONNECTED) {
// wifi_event_ap_staconnected_t* event = (wifi_event_ap_staconnected_t*) event_data;
// ESP_LOGI(TAG, "station "MACSTR" join, AID=%d",
// MAC2STR(event->mac), event->aid);
// } else if (event_id == WIFI_EVENT_AP_STADISCONNECTED) {
// wifi_event_ap_stadisconnected_t* event = (wifi_event_ap_stadisconnected_t*) event_data;
// ESP_LOGI(TAG, "station "MACSTR" leave, AID=%d",
// MAC2STR(event->mac), event->aid);
// }
}
extern void ModBusTCPSlave_init(void);
void wifi_init_softap(void)
{
ESP_ERROR_CHECK(esp_netif_init());

1388
sdkconfig

File diff suppressed because it is too large Load Diff