1
0
mirror of https://github.com/esphome/esphome.git synced 2025-09-26 15:12:21 +01:00

Merge branch 'dev' into integration

This commit is contained in:
J. Nick Koston
2025-06-20 21:36:36 +02:00
29 changed files with 457 additions and 327 deletions

View File

@@ -86,7 +86,7 @@ bool AudioTransferBuffer::reallocate(size_t new_buffer_size) {
bool AudioTransferBuffer::allocate_buffer_(size_t buffer_size) {
this->buffer_size_ = buffer_size;
RAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
this->buffer_ = allocator.allocate(this->buffer_size_);
if (this->buffer_ == nullptr) {
@@ -101,7 +101,7 @@ bool AudioTransferBuffer::allocate_buffer_(size_t buffer_size) {
void AudioTransferBuffer::deallocate_buffer_() {
if (this->buffer_ != nullptr) {
RAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
allocator.deallocate(this->buffer_, this->buffer_size_);
this->buffer_ = nullptr;
this->data_start_ = nullptr;

View File

@@ -50,7 +50,7 @@ void BH1750Sensor::read_lx_(BH1750Mode mode, uint8_t mtreg, const std::function<
// turn on (after one-shot sensor automatically powers down)
uint8_t turn_on = BH1750_COMMAND_POWER_ON;
if (this->write(&turn_on, 1) != i2c::ERROR_OK) {
ESP_LOGW(TAG, "Turning on BH1750 failed");
ESP_LOGW(TAG, "Power on failed");
f(NAN);
return;
}
@@ -60,7 +60,7 @@ void BH1750Sensor::read_lx_(BH1750Mode mode, uint8_t mtreg, const std::function<
uint8_t mtreg_hi = BH1750_COMMAND_MT_REG_HI | ((mtreg >> 5) & 0b111);
uint8_t mtreg_lo = BH1750_COMMAND_MT_REG_LO | ((mtreg >> 0) & 0b11111);
if (this->write(&mtreg_hi, 1) != i2c::ERROR_OK || this->write(&mtreg_lo, 1) != i2c::ERROR_OK) {
ESP_LOGW(TAG, "Setting measurement time for BH1750 failed");
ESP_LOGW(TAG, "Set measurement time failed");
active_mtreg_ = 0;
f(NAN);
return;
@@ -88,7 +88,7 @@ void BH1750Sensor::read_lx_(BH1750Mode mode, uint8_t mtreg, const std::function<
return;
}
if (this->write(&cmd, 1) != i2c::ERROR_OK) {
ESP_LOGW(TAG, "Starting measurement for BH1750 failed");
ESP_LOGW(TAG, "Start measurement failed");
f(NAN);
return;
}
@@ -99,7 +99,7 @@ void BH1750Sensor::read_lx_(BH1750Mode mode, uint8_t mtreg, const std::function<
this->set_timeout("read", meas_time, [this, mode, mtreg, f]() {
uint16_t raw_value;
if (this->read(reinterpret_cast<uint8_t *>(&raw_value), 2) != i2c::ERROR_OK) {
ESP_LOGW(TAG, "Reading BH1750 data failed");
ESP_LOGW(TAG, "Read data failed");
f(NAN);
return;
}
@@ -156,7 +156,7 @@ void BH1750Sensor::update() {
this->publish_state(NAN);
return;
}
ESP_LOGD(TAG, "'%s': Got illuminance=%.1flx", this->get_name().c_str(), val);
ESP_LOGD(TAG, "'%s': Illuminance=%.1flx", this->get_name().c_str(), val);
this->status_clear_warning();
this->publish_state(val);
});

View File

@@ -11,7 +11,7 @@ namespace display {
static const char *const TAG = "display";
void DisplayBuffer::init_internal_(uint32_t buffer_length) {
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
this->buffer_ = allocator.allocate(buffer_length);
if (this->buffer_ == nullptr) {
ESP_LOGE(TAG, "Could not allocate buffer for display!");

View File

@@ -1,5 +1,6 @@
from esphome import automation, pins
import esphome.codegen as cg
from esphome.components import i2c
from esphome.components.esp32 import add_idf_component
import esphome.config_validation as cv
from esphome.const import (
@@ -7,6 +8,7 @@ from esphome.const import (
CONF_CONTRAST,
CONF_DATA_PINS,
CONF_FREQUENCY,
CONF_I2C_ID,
CONF_ID,
CONF_PIN,
CONF_RESET_PIN,
@@ -149,93 +151,104 @@ CONF_ON_IMAGE = "on_image"
camera_range_param = cv.int_range(min=-2, max=2)
CONFIG_SCHEMA = cv.ENTITY_BASE_SCHEMA.extend(
{
cv.GenerateID(): cv.declare_id(ESP32Camera),
# pin assignment
cv.Required(CONF_DATA_PINS): cv.All(
[pins.internal_gpio_input_pin_number], cv.Length(min=8, max=8)
),
cv.Required(CONF_VSYNC_PIN): pins.internal_gpio_input_pin_number,
cv.Required(CONF_HREF_PIN): pins.internal_gpio_input_pin_number,
cv.Required(CONF_PIXEL_CLOCK_PIN): pins.internal_gpio_input_pin_number,
cv.Required(CONF_EXTERNAL_CLOCK): cv.Schema(
{
cv.Required(CONF_PIN): pins.internal_gpio_input_pin_number,
cv.Optional(CONF_FREQUENCY, default="20MHz"): cv.All(
cv.frequency, cv.Range(min=8e6, max=20e6)
),
}
),
cv.Required(CONF_I2C_PINS): cv.Schema(
{
cv.Required(CONF_SDA): pins.internal_gpio_output_pin_number,
cv.Required(CONF_SCL): pins.internal_gpio_output_pin_number,
}
),
cv.Optional(CONF_RESET_PIN): pins.internal_gpio_output_pin_number,
cv.Optional(CONF_POWER_DOWN_PIN): pins.internal_gpio_output_pin_number,
# image
cv.Optional(CONF_RESOLUTION, default="640X480"): cv.enum(
FRAME_SIZES, upper=True
),
cv.Optional(CONF_JPEG_QUALITY, default=10): cv.int_range(min=6, max=63),
cv.Optional(CONF_CONTRAST, default=0): camera_range_param,
cv.Optional(CONF_BRIGHTNESS, default=0): camera_range_param,
cv.Optional(CONF_SATURATION, default=0): camera_range_param,
cv.Optional(CONF_VERTICAL_FLIP, default=True): cv.boolean,
cv.Optional(CONF_HORIZONTAL_MIRROR, default=True): cv.boolean,
cv.Optional(CONF_SPECIAL_EFFECT, default="NONE"): cv.enum(
ENUM_SPECIAL_EFFECT, upper=True
),
# exposure
cv.Optional(CONF_AGC_MODE, default="AUTO"): cv.enum(
ENUM_GAIN_CONTROL_MODE, upper=True
),
cv.Optional(CONF_AEC2, default=False): cv.boolean,
cv.Optional(CONF_AE_LEVEL, default=0): camera_range_param,
cv.Optional(CONF_AEC_VALUE, default=300): cv.int_range(min=0, max=1200),
# gains
cv.Optional(CONF_AEC_MODE, default="AUTO"): cv.enum(
ENUM_GAIN_CONTROL_MODE, upper=True
),
cv.Optional(CONF_AGC_VALUE, default=0): cv.int_range(min=0, max=30),
cv.Optional(CONF_AGC_GAIN_CEILING, default="2X"): cv.enum(
ENUM_GAIN_CEILING, upper=True
),
# white balance
cv.Optional(CONF_WB_MODE, default="AUTO"): cv.enum(ENUM_WB_MODE, upper=True),
# test pattern
cv.Optional(CONF_TEST_PATTERN, default=False): cv.boolean,
# framerates
cv.Optional(CONF_MAX_FRAMERATE, default="10 fps"): cv.All(
cv.framerate, cv.Range(min=0, min_included=False, max=60)
),
cv.Optional(CONF_IDLE_FRAMERATE, default="0.1 fps"): cv.All(
cv.framerate, cv.Range(min=0, max=1)
),
cv.Optional(CONF_FRAME_BUFFER_COUNT, default=1): cv.int_range(min=1, max=2),
cv.Optional(CONF_ON_STREAM_START): automation.validate_automation(
{
cv.GenerateID(CONF_TRIGGER_ID): cv.declare_id(
ESP32CameraStreamStartTrigger
),
}
),
cv.Optional(CONF_ON_STREAM_STOP): automation.validate_automation(
{
cv.GenerateID(CONF_TRIGGER_ID): cv.declare_id(
ESP32CameraStreamStopTrigger
),
}
),
cv.Optional(CONF_ON_IMAGE): automation.validate_automation(
{
cv.GenerateID(CONF_TRIGGER_ID): cv.declare_id(ESP32CameraImageTrigger),
}
),
}
).extend(cv.COMPONENT_SCHEMA)
CONFIG_SCHEMA = cv.All(
cv.ENTITY_BASE_SCHEMA.extend(
{
cv.GenerateID(): cv.declare_id(ESP32Camera),
# pin assignment
cv.Required(CONF_DATA_PINS): cv.All(
[pins.internal_gpio_input_pin_number], cv.Length(min=8, max=8)
),
cv.Required(CONF_VSYNC_PIN): pins.internal_gpio_input_pin_number,
cv.Required(CONF_HREF_PIN): pins.internal_gpio_input_pin_number,
cv.Required(CONF_PIXEL_CLOCK_PIN): pins.internal_gpio_input_pin_number,
cv.Required(CONF_EXTERNAL_CLOCK): cv.Schema(
{
cv.Required(CONF_PIN): pins.internal_gpio_input_pin_number,
cv.Optional(CONF_FREQUENCY, default="20MHz"): cv.All(
cv.frequency, cv.Range(min=8e6, max=20e6)
),
}
),
cv.Optional(CONF_I2C_PINS): cv.Schema(
{
cv.Required(CONF_SDA): pins.internal_gpio_output_pin_number,
cv.Required(CONF_SCL): pins.internal_gpio_output_pin_number,
}
),
cv.Optional(CONF_I2C_ID): cv.Any(
cv.use_id(i2c.InternalI2CBus),
msg="I2C bus must be an internal ESP32 I2C bus",
),
cv.Optional(CONF_RESET_PIN): pins.internal_gpio_output_pin_number,
cv.Optional(CONF_POWER_DOWN_PIN): pins.internal_gpio_output_pin_number,
# image
cv.Optional(CONF_RESOLUTION, default="640X480"): cv.enum(
FRAME_SIZES, upper=True
),
cv.Optional(CONF_JPEG_QUALITY, default=10): cv.int_range(min=6, max=63),
cv.Optional(CONF_CONTRAST, default=0): camera_range_param,
cv.Optional(CONF_BRIGHTNESS, default=0): camera_range_param,
cv.Optional(CONF_SATURATION, default=0): camera_range_param,
cv.Optional(CONF_VERTICAL_FLIP, default=True): cv.boolean,
cv.Optional(CONF_HORIZONTAL_MIRROR, default=True): cv.boolean,
cv.Optional(CONF_SPECIAL_EFFECT, default="NONE"): cv.enum(
ENUM_SPECIAL_EFFECT, upper=True
),
# exposure
cv.Optional(CONF_AGC_MODE, default="AUTO"): cv.enum(
ENUM_GAIN_CONTROL_MODE, upper=True
),
cv.Optional(CONF_AEC2, default=False): cv.boolean,
cv.Optional(CONF_AE_LEVEL, default=0): camera_range_param,
cv.Optional(CONF_AEC_VALUE, default=300): cv.int_range(min=0, max=1200),
# gains
cv.Optional(CONF_AEC_MODE, default="AUTO"): cv.enum(
ENUM_GAIN_CONTROL_MODE, upper=True
),
cv.Optional(CONF_AGC_VALUE, default=0): cv.int_range(min=0, max=30),
cv.Optional(CONF_AGC_GAIN_CEILING, default="2X"): cv.enum(
ENUM_GAIN_CEILING, upper=True
),
# white balance
cv.Optional(CONF_WB_MODE, default="AUTO"): cv.enum(
ENUM_WB_MODE, upper=True
),
# test pattern
cv.Optional(CONF_TEST_PATTERN, default=False): cv.boolean,
# framerates
cv.Optional(CONF_MAX_FRAMERATE, default="10 fps"): cv.All(
cv.framerate, cv.Range(min=0, min_included=False, max=60)
),
cv.Optional(CONF_IDLE_FRAMERATE, default="0.1 fps"): cv.All(
cv.framerate, cv.Range(min=0, max=1)
),
cv.Optional(CONF_FRAME_BUFFER_COUNT, default=1): cv.int_range(min=1, max=2),
cv.Optional(CONF_ON_STREAM_START): automation.validate_automation(
{
cv.GenerateID(CONF_TRIGGER_ID): cv.declare_id(
ESP32CameraStreamStartTrigger
),
}
),
cv.Optional(CONF_ON_STREAM_STOP): automation.validate_automation(
{
cv.GenerateID(CONF_TRIGGER_ID): cv.declare_id(
ESP32CameraStreamStopTrigger
),
}
),
cv.Optional(CONF_ON_IMAGE): automation.validate_automation(
{
cv.GenerateID(CONF_TRIGGER_ID): cv.declare_id(
ESP32CameraImageTrigger
),
}
),
}
).extend(cv.COMPONENT_SCHEMA),
cv.has_exactly_one_key(CONF_I2C_PINS, CONF_I2C_ID),
)
SETTERS = {
# pin assignment
@@ -280,8 +293,12 @@ async def to_code(config):
extclk = config[CONF_EXTERNAL_CLOCK]
cg.add(var.set_external_clock(extclk[CONF_PIN], extclk[CONF_FREQUENCY]))
i2c_pins = config[CONF_I2C_PINS]
cg.add(var.set_i2c_pins(i2c_pins[CONF_SDA], i2c_pins[CONF_SCL]))
if i2c_id := config.get(CONF_I2C_ID):
i2c_hub = await cg.get_variable(i2c_id)
cg.add(var.set_i2c_id(i2c_hub))
else:
i2c_pins = config[CONF_I2C_PINS]
cg.add(var.set_i2c_pins(i2c_pins[CONF_SDA], i2c_pins[CONF_SCL]))
cg.add(var.set_max_update_interval(1000 / config[CONF_MAX_FRAMERATE]))
if config[CONF_IDLE_FRAMERATE] == 0:
cg.add(var.set_idle_update_interval(0))

View File

@@ -1,9 +1,9 @@
#ifdef USE_ESP32
#include "esp32_camera.h"
#include "esphome/core/log.h"
#include "esphome/core/hal.h"
#include "esphome/core/application.h"
#include "esphome/core/hal.h"
#include "esphome/core/log.h"
#include <freertos/task.h>
@@ -16,6 +16,12 @@ static const char *const TAG = "esp32_camera";
void ESP32Camera::setup() {
global_esp32_camera = this;
#ifdef USE_I2C
if (this->i2c_bus_ != nullptr) {
this->config_.sccb_i2c_port = this->i2c_bus_->get_port();
}
#endif
/* initialize time to now */
this->last_update_ = millis();
@@ -246,6 +252,13 @@ void ESP32Camera::set_i2c_pins(uint8_t sda, uint8_t scl) {
this->config_.pin_sccb_sda = sda;
this->config_.pin_sccb_scl = scl;
}
#ifdef USE_I2C
void ESP32Camera::set_i2c_id(i2c::InternalI2CBus *i2c_bus) {
this->i2c_bus_ = i2c_bus;
this->config_.pin_sccb_sda = -1;
this->config_.pin_sccb_scl = -1;
}
#endif // USE_I2C
void ESP32Camera::set_reset_pin(uint8_t pin) { this->config_.pin_reset = pin; }
void ESP32Camera::set_power_down_pin(uint8_t pin) { this->config_.pin_pwdn = pin; }

View File

@@ -2,13 +2,17 @@
#ifdef USE_ESP32
#include <esp_camera.h>
#include <freertos/FreeRTOS.h>
#include <freertos/queue.h>
#include "esphome/core/automation.h"
#include "esphome/core/component.h"
#include "esphome/core/entity_base.h"
#include "esphome/core/helpers.h"
#include <esp_camera.h>
#include <freertos/FreeRTOS.h>
#include <freertos/queue.h>
#ifdef USE_I2C
#include "esphome/components/i2c/i2c_bus.h"
#endif // USE_I2C
namespace esphome {
namespace esp32_camera {
@@ -118,6 +122,9 @@ class ESP32Camera : public EntityBase, public Component {
void set_pixel_clock_pin(uint8_t pin);
void set_external_clock(uint8_t pin, uint32_t frequency);
void set_i2c_pins(uint8_t sda, uint8_t scl);
#ifdef USE_I2C
void set_i2c_id(i2c::InternalI2CBus *i2c_bus);
#endif // USE_I2C
void set_reset_pin(uint8_t pin);
void set_power_down_pin(uint8_t pin);
/* -- image */
@@ -210,6 +217,9 @@ class ESP32Camera : public EntityBase, public Component {
uint32_t last_idle_request_{0};
uint32_t last_update_{0};
#ifdef USE_I2C
i2c::InternalI2CBus *i2c_bus_{nullptr};
#endif // USE_I2C
};
// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)

View File

@@ -67,10 +67,10 @@ class Font
inline int get_height() { return this->height_; }
inline int get_bpp() { return this->bpp_; }
const std::vector<Glyph, ExternalRAMAllocator<Glyph>> &get_glyphs() const { return glyphs_; }
const std::vector<Glyph, RAMAllocator<Glyph>> &get_glyphs() const { return glyphs_; }
protected:
std::vector<Glyph, ExternalRAMAllocator<Glyph>> glyphs_;
std::vector<Glyph, RAMAllocator<Glyph>> glyphs_;
int baseline_;
int height_;
uint8_t bpp_; // bits per pixel

View File

@@ -239,7 +239,7 @@ template<typename... Ts> class HttpRequestSendAction : public Action<Ts...> {
std::string response_body;
if (this->capture_response_.value(x...)) {
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
uint8_t *buf = allocator.allocate(max_length);
if (buf != nullptr) {
size_t read_index = 0;

View File

@@ -54,7 +54,7 @@ void HttpRequestUpdate::update_task(void *params) {
UPDATE_RETURN;
}
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
uint8_t *data = allocator.allocate(container->content_length);
if (data == nullptr) {
std::string msg = str_sprintf("Failed to allocate %d bytes for manifest", container->content_length);

View File

@@ -109,6 +109,7 @@ class I2CBus {
};
class InternalI2CBus : public I2CBus {
public:
/// @brief Returns the I2C port number.
/// @return the port number of the internal I2C bus
virtual int get_port() const = 0;

View File

@@ -484,7 +484,7 @@ bool I2SAudioSpeaker::send_esp_err_to_event_group_(esp_err_t err) {
esp_err_t I2SAudioSpeaker::allocate_buffers_(size_t data_buffer_size, size_t ring_buffer_size) {
if (this->data_buffer_ == nullptr) {
// Allocate data buffer for temporarily storing audio from the ring buffer before writing to the I2S bus
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
this->data_buffer_ = allocator.allocate(data_buffer_size);
}
@@ -698,7 +698,7 @@ void I2SAudioSpeaker::delete_task_(size_t buffer_size) {
this->audio_ring_buffer_.reset(); // Releases ownership of the shared_ptr
if (this->data_buffer_ != nullptr) {
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
allocator.deallocate(this->data_buffer_, buffer_size);
this->data_buffer_ = nullptr;
}

View File

@@ -57,8 +57,8 @@ void Inkplate6::setup() {
* Allocate buffers. May be called after setup to re-initialise if e.g. greyscale is changed.
*/
void Inkplate6::initialize_() {
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
ExternalRAMAllocator<uint32_t> allocator32(ExternalRAMAllocator<uint32_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
RAMAllocator<uint32_t> allocator32;
uint32_t buffer_size = this->get_buffer_length_();
if (buffer_size == 0)
return;

View File

@@ -27,7 +27,7 @@ void VADModel::log_model_config() {
}
bool StreamingModel::load_model_() {
RAMAllocator<uint8_t> arena_allocator(RAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> arena_allocator;
if (this->tensor_arena_ == nullptr) {
this->tensor_arena_ = arena_allocator.allocate(this->tensor_arena_size_);
@@ -96,7 +96,7 @@ bool StreamingModel::load_model_() {
void StreamingModel::unload_model() {
this->interpreter_.reset();
RAMAllocator<uint8_t> arena_allocator(RAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> arena_allocator;
if (this->tensor_arena_ != nullptr) {
arena_allocator.deallocate(this->tensor_arena_, this->tensor_arena_size_);

View File

@@ -1,8 +1,8 @@
#include "nextion.h"
#include "esphome/core/util.h"
#include "esphome/core/log.h"
#include "esphome/core/application.h"
#include <cinttypes>
#include "esphome/core/application.h"
#include "esphome/core/log.h"
#include "esphome/core/util.h"
namespace esphome {
namespace nextion {
@@ -71,13 +71,13 @@ bool Nextion::check_connect_() {
}
this->send_command_("connect");
this->comok_sent_ = millis();
this->comok_sent_ = App.get_loop_component_start_time();
this->ignore_is_setup_ = false;
return false;
}
if (millis() - this->comok_sent_ <= 500) // Wait 500 ms
if (App.get_loop_component_start_time() - this->comok_sent_ <= 500) // Wait 500 ms
return false;
std::string response;
@@ -318,15 +318,38 @@ void Nextion::loop() {
if (!this->nextion_reports_is_setup_) {
if (this->started_ms_ == 0)
this->started_ms_ = millis();
this->started_ms_ = App.get_loop_component_start_time();
if (this->started_ms_ + this->startup_override_ms_ < millis()) {
if (this->started_ms_ + this->startup_override_ms_ < App.get_loop_component_start_time()) {
ESP_LOGD(TAG, "Manual ready set");
this->nextion_reports_is_setup_ = true;
}
}
#ifdef USE_NEXTION_COMMAND_SPACING
// Try to send any pending commands if spacing allows
this->process_pending_in_queue_();
#endif // USE_NEXTION_COMMAND_SPACING
}
#ifdef USE_NEXTION_COMMAND_SPACING
void Nextion::process_pending_in_queue_() {
if (this->nextion_queue_.empty() || !this->command_pacer_.can_send()) {
return;
}
// Check if first item in queue has a pending command
auto *front_item = this->nextion_queue_.front();
if (front_item && !front_item->pending_command.empty()) {
if (this->send_command_(front_item->pending_command)) {
// Command sent successfully, clear the pending command
front_item->pending_command.clear();
ESP_LOGVV(TAG, "Pending command sent: %s", front_item->component->get_variable_name().c_str());
}
}
}
#endif // USE_NEXTION_COMMAND_SPACING
bool Nextion::remove_from_q_(bool report_empty) {
if (this->nextion_queue_.empty()) {
if (report_empty) {
@@ -409,7 +432,7 @@ void Nextion::process_nextion_commands_() {
case 0x01: // instruction sent by user was successful
ESP_LOGVV(TAG, "Cmd OK");
ESP_LOGN(TAG, "this->nextion_queue_.empty() %s", this->nextion_queue_.empty() ? "True" : "False");
ESP_LOGN(TAG, "this->nextion_queue_.empty() %s", YESNO(this->nextion_queue_.empty()));
this->remove_from_q_();
if (!this->is_setup_) {
@@ -421,7 +444,7 @@ void Nextion::process_nextion_commands_() {
}
#ifdef USE_NEXTION_COMMAND_SPACING
this->command_pacer_.mark_sent(); // Here is where we should mark the command as sent
ESP_LOGN(TAG, "Command spacing: marked command sent at %u ms", millis());
ESP_LOGN(TAG, "Command spacing: marked command sent");
#endif
break;
case 0x02: // invalid Component ID or name was used
@@ -805,7 +828,7 @@ void Nextion::process_nextion_commands_() {
this->command_data_.erase(0, to_process_length + COMMAND_DELIMITER.length() + 1);
}
uint32_t ms = millis();
uint32_t ms = App.get_loop_component_start_time();
if (!this->nextion_queue_.empty() && this->nextion_queue_.front()->queue_time + this->max_q_age_ms_ < ms) {
for (size_t i = 0; i < this->nextion_queue_.size(); i++) {
@@ -944,9 +967,9 @@ uint16_t Nextion::recv_ret_string_(std::string &response, uint32_t timeout, bool
bool exit_flag = false;
bool ff_flag = false;
start = millis();
start = App.get_loop_component_start_time();
while ((timeout == 0 && this->available()) || millis() - start <= timeout) {
while ((timeout == 0 && this->available()) || App.get_loop_component_start_time() - start <= timeout) {
if (!this->available()) {
App.feed_wdt();
delay(1);
@@ -1003,7 +1026,7 @@ void Nextion::add_no_result_to_queue_(const std::string &variable_name) {
}
#endif
ExternalRAMAllocator<nextion::NextionQueue> allocator(ExternalRAMAllocator<nextion::NextionQueue>::ALLOW_FAILURE);
RAMAllocator<nextion::NextionQueue> allocator;
nextion::NextionQueue *nextion_queue = allocator.allocate(1);
if (nextion_queue == nullptr) {
ESP_LOGW(TAG, "Queue alloc failed");
@@ -1015,7 +1038,7 @@ void Nextion::add_no_result_to_queue_(const std::string &variable_name) {
nextion_queue->component = new nextion::NextionComponentBase;
nextion_queue->component->set_variable_name(variable_name);
nextion_queue->queue_time = millis();
nextion_queue->queue_time = App.get_loop_component_start_time();
this->nextion_queue_.push_back(nextion_queue);
@@ -1034,9 +1057,42 @@ void Nextion::add_no_result_to_queue_with_command_(const std::string &variable_n
if (this->send_command_(command)) {
this->add_no_result_to_queue_(variable_name);
#ifdef USE_NEXTION_COMMAND_SPACING
} else {
// Command blocked by spacing, add to queue WITH the command for retry
this->add_no_result_to_queue_with_pending_command_(variable_name, command);
#endif // USE_NEXTION_COMMAND_SPACING
}
}
#ifdef USE_NEXTION_COMMAND_SPACING
void Nextion::add_no_result_to_queue_with_pending_command_(const std::string &variable_name,
const std::string &command) {
#ifdef USE_NEXTION_MAX_QUEUE_SIZE
if (this->max_queue_size_ > 0 && this->nextion_queue_.size() >= this->max_queue_size_) {
ESP_LOGW(TAG, "Queue full (%zu), drop: %s", this->nextion_queue_.size(), variable_name.c_str());
return;
}
#endif
RAMAllocator<nextion::NextionQueue> allocator;
nextion::NextionQueue *nextion_queue = allocator.allocate(1);
if (nextion_queue == nullptr) {
ESP_LOGW(TAG, "Queue alloc failed");
return;
}
new (nextion_queue) nextion::NextionQueue();
nextion_queue->component = new nextion::NextionComponentBase;
nextion_queue->component->set_variable_name(variable_name);
nextion_queue->queue_time = App.get_loop_component_start_time();
nextion_queue->pending_command = command; // Store command for retry
this->nextion_queue_.push_back(nextion_queue);
ESP_LOGVV(TAG, "Queue with pending command: %s", variable_name.c_str());
}
#endif // USE_NEXTION_COMMAND_SPACING
bool Nextion::add_no_result_to_queue_with_ignore_sleep_printf_(const std::string &variable_name, const char *format,
...) {
if ((!this->is_setup() && !this->ignore_is_setup_))
@@ -1159,7 +1215,7 @@ void Nextion::add_to_get_queue(NextionComponentBase *component) {
}
#endif
ExternalRAMAllocator<nextion::NextionQueue> allocator(ExternalRAMAllocator<nextion::NextionQueue>::ALLOW_FAILURE);
RAMAllocator<nextion::NextionQueue> allocator;
nextion::NextionQueue *nextion_queue = allocator.allocate(1);
if (nextion_queue == nullptr) {
ESP_LOGW(TAG, "Queue alloc failed");
@@ -1168,7 +1224,7 @@ void Nextion::add_to_get_queue(NextionComponentBase *component) {
new (nextion_queue) nextion::NextionQueue();
nextion_queue->component = component;
nextion_queue->queue_time = millis();
nextion_queue->queue_time = App.get_loop_component_start_time();
ESP_LOGN(TAG, "Queue %s: %s", component->get_queue_type_string().c_str(), component->get_variable_name().c_str());
@@ -1191,7 +1247,7 @@ void Nextion::add_addt_command_to_queue(NextionComponentBase *component) {
if ((!this->is_setup() && !this->ignore_is_setup_) || this->is_sleeping())
return;
ExternalRAMAllocator<nextion::NextionQueue> allocator(ExternalRAMAllocator<nextion::NextionQueue>::ALLOW_FAILURE);
RAMAllocator<nextion::NextionQueue> allocator;
nextion::NextionQueue *nextion_queue = allocator.allocate(1);
if (nextion_queue == nullptr) {
ESP_LOGW(TAG, "Queue alloc failed");
@@ -1200,7 +1256,7 @@ void Nextion::add_addt_command_to_queue(NextionComponentBase *component) {
new (nextion_queue) nextion::NextionQueue();
nextion_queue->component = component;
nextion_queue->queue_time = millis();
nextion_queue->queue_time = App.get_loop_component_start_time();
this->waveform_queue_.push_back(nextion_queue);
if (this->waveform_queue_.size() == 1)

View File

@@ -1309,9 +1309,23 @@ class Nextion : public NextionBase, public PollingComponent, public uart::UARTDe
#ifdef USE_NEXTION_MAX_QUEUE_SIZE
size_t max_queue_size_{0};
#endif // USE_NEXTION_MAX_QUEUE_SIZE
#ifdef USE_NEXTION_COMMAND_SPACING
NextionCommandPacer command_pacer_{0};
/**
* @brief Process any commands in the queue that are pending due to command spacing
*
* This method checks if the first item in the nextion_queue_ has a pending command
* that was previously blocked by command spacing. If spacing now allows and a
* pending command exists, it attempts to send the command. Once successfully sent,
* the pending command is cleared and the queue item continues normal processing.
*
* Called from loop() to retry sending commands that were delayed by spacing.
*/
void process_pending_in_queue_();
#endif // USE_NEXTION_COMMAND_SPACING
std::deque<NextionQueue *> nextion_queue_;
std::deque<NextionQueue *> waveform_queue_;
uint16_t recv_ret_string_(std::string &response, uint32_t timeout, bool recv_flag);
@@ -1348,6 +1362,23 @@ class Nextion : public NextionBase, public PollingComponent, public uart::UARTDe
__attribute__((format(printf, 3, 4)));
void add_no_result_to_queue_with_command_(const std::string &variable_name, const std::string &command);
#ifdef USE_NEXTION_COMMAND_SPACING
/**
* @brief Add a command to the Nextion queue with a pending command for retry
*
* This method creates a queue entry for a command that was blocked by command spacing.
* The command string is stored in the queue item's pending_command field so it can
* be retried later when spacing allows. This ensures commands are not lost when
* sent too quickly.
*
* If the max_queue_size limit is configured and reached, the command will be dropped.
*
* @param variable_name Name of the variable or component associated with the command
* @param command The actual command string to be sent when spacing allows
*/
void add_no_result_to_queue_with_pending_command_(const std::string &variable_name, const std::string &command);
#endif // USE_NEXTION_COMMAND_SPACING
bool add_no_result_to_queue_with_printf_(const std::string &variable_name, const char *format, ...)
__attribute__((format(printf, 3, 4)));

View File

@@ -25,6 +25,9 @@ class NextionQueue {
virtual ~NextionQueue() = default;
NextionComponentBase *component;
uint32_t queue_time = 0;
// Store command for retry if spacing blocked it
std::string pending_command; // Empty if command was sent successfully
};
class NextionComponentBase {

View File

@@ -3,12 +3,12 @@
#ifdef USE_NEXTION_TFT_UPLOAD
#ifdef USE_ARDUINO
#include <cinttypes>
#include "esphome/components/network/util.h"
#include "esphome/core/application.h"
#include "esphome/core/defines.h"
#include "esphome/core/util.h"
#include "esphome/core/log.h"
#include "esphome/components/network/util.h"
#include <cinttypes>
#include "esphome/core/util.h"
#ifdef USE_ESP32
#include <esp_heap_caps.h>
@@ -52,7 +52,7 @@ int Nextion::upload_by_chunks_(HTTPClient &http_client, uint32_t &range_start) {
}
// Allocate the buffer dynamically
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
uint8_t *buffer = allocator.allocate(4096);
if (!buffer) {
ESP_LOGE(TAG, "Buffer alloc failed");
@@ -67,8 +67,8 @@ int Nextion::upload_by_chunks_(HTTPClient &http_client, uint32_t &range_start) {
ESP_LOGV(TAG, "Fetch %" PRIu16 " bytes", buffer_size);
uint16_t read_len = 0;
int partial_read_len = 0;
const uint32_t start_time = millis();
while (read_len < buffer_size && millis() - start_time < 5000) {
const uint32_t start_time = App.get_loop_component_start_time();
while (read_len < buffer_size && App.get_loop_component_start_time() - start_time < 5000) {
if (http_client.getStreamPtr()->available() > 0) {
partial_read_len =
http_client.getStreamPtr()->readBytes(reinterpret_cast<char *>(buffer) + read_len, buffer_size - read_len);

View File

@@ -3,14 +3,14 @@
#ifdef USE_NEXTION_TFT_UPLOAD
#ifdef USE_ESP_IDF
#include "esphome/core/application.h"
#include "esphome/core/defines.h"
#include "esphome/core/util.h"
#include "esphome/core/log.h"
#include "esphome/components/network/util.h"
#include <cinttypes>
#include <esp_heap_caps.h>
#include <esp_http_client.h>
#include <cinttypes>
#include "esphome/components/network/util.h"
#include "esphome/core/application.h"
#include "esphome/core/defines.h"
#include "esphome/core/log.h"
#include "esphome/core/util.h"
namespace esphome {
namespace nextion {
@@ -51,7 +51,7 @@ int Nextion::upload_by_chunks_(esp_http_client_handle_t http_client, uint32_t &r
}
// Allocate the buffer dynamically
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
uint8_t *buffer = allocator.allocate(4096);
if (!buffer) {
ESP_LOGE(TAG, "Buffer alloc failed");

View File

@@ -19,6 +19,7 @@ USBClient = usb_host_ns.class_("USBClient", Component)
CONF_DEVICES = "devices"
CONF_VID = "vid"
CONF_PID = "pid"
CONF_ENABLE_HUBS = "enable_hubs"
def usb_device_schema(cls=USBClient, vid: int = None, pid: [int] = None) -> cv.Schema:
@@ -42,6 +43,7 @@ CONFIG_SCHEMA = cv.All(
cv.COMPONENT_SCHEMA.extend(
{
cv.GenerateID(): cv.declare_id(USBHost),
cv.Optional(CONF_ENABLE_HUBS, default=False): cv.boolean,
cv.Optional(CONF_DEVICES): cv.ensure_list(usb_device_schema()),
}
),
@@ -58,6 +60,8 @@ async def register_usb_client(config):
async def to_code(config):
add_idf_sdkconfig_option("CONFIG_USB_HOST_CONTROL_TRANSFER_MAX_SIZE", 1024)
if config.get(CONF_ENABLE_HUBS):
add_idf_sdkconfig_option("CONFIG_USB_HOST_HUBS_SUPPORTED", True)
var = cg.new_Pvariable(config[CONF_ID])
await cg.register_component(var, config)
for device in config.get(CONF_DEVICES) or ():

View File

@@ -85,7 +85,7 @@ bool VoiceAssistant::start_udp_socket_() {
bool VoiceAssistant::allocate_buffers_() {
#ifdef USE_SPEAKER
if ((this->speaker_ != nullptr) && (this->speaker_buffer_ == nullptr)) {
ExternalRAMAllocator<uint8_t> speaker_allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> speaker_allocator;
this->speaker_buffer_ = speaker_allocator.allocate(SPEAKER_BUFFER_SIZE);
if (this->speaker_buffer_ == nullptr) {
ESP_LOGW(TAG, "Could not allocate speaker buffer");
@@ -103,7 +103,7 @@ bool VoiceAssistant::allocate_buffers_() {
}
if (this->send_buffer_ == nullptr) {
ExternalRAMAllocator<uint8_t> send_allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> send_allocator;
this->send_buffer_ = send_allocator.allocate(SEND_BUFFER_SIZE);
if (send_buffer_ == nullptr) {
ESP_LOGW(TAG, "Could not allocate send buffer");
@@ -136,7 +136,7 @@ void VoiceAssistant::clear_buffers_() {
void VoiceAssistant::deallocate_buffers_() {
if (this->send_buffer_ != nullptr) {
ExternalRAMAllocator<uint8_t> send_deallocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> send_deallocator;
send_deallocator.deallocate(this->send_buffer_, SEND_BUFFER_SIZE);
this->send_buffer_ = nullptr;
}
@@ -147,7 +147,7 @@ void VoiceAssistant::deallocate_buffers_() {
#ifdef USE_SPEAKER
if ((this->speaker_ != nullptr) && (this->speaker_buffer_ != nullptr)) {
ExternalRAMAllocator<uint8_t> speaker_deallocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> speaker_deallocator;
speaker_deallocator.deallocate(this->speaker_buffer_, SPEAKER_BUFFER_SIZE);
this->speaker_buffer_ = nullptr;
}

View File

@@ -1,9 +1,9 @@
#include "waveshare_epaper.h"
#include <bitset>
#include <cinttypes>
#include "esphome/core/application.h"
#include "esphome/core/helpers.h"
#include "esphome/core/log.h"
#include <cinttypes>
#include <bitset>
namespace esphome {
namespace waveshare_epaper {
@@ -185,7 +185,7 @@ void WaveshareEPaper7C::setup() {
this->initialize();
}
void WaveshareEPaper7C::init_internal_7c_(uint32_t buffer_length) {
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
uint32_t small_buffer_length = buffer_length / NUM_BUFFERS;
for (int i = 0; i < NUM_BUFFERS; i++) {
@@ -2054,7 +2054,7 @@ void GDEW029T5::initialize() {
this->deep_sleep_between_updates_ = true;
// old buffer for partial update
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
this->old_buffer_ = allocator.allocate(this->get_buffer_length_());
if (this->old_buffer_ == nullptr) {
ESP_LOGE(TAG, "Could not allocate old buffer for display!");
@@ -2199,7 +2199,7 @@ void GDEW029T5::dump_config() {
void GDEW0154M09::initialize() {
this->init_internal_();
ExternalRAMAllocator<uint8_t> allocator(ExternalRAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
this->lastbuff_ = allocator.allocate(this->get_buffer_length_());
if (this->lastbuff_ != nullptr) {
memset(this->lastbuff_, 0xff, sizeof(uint8_t) * this->get_buffer_length_());

View File

@@ -73,7 +73,7 @@ void WiFiComponent::start() {
SavedWifiSettings save{};
if (this->pref_.load(&save)) {
ESP_LOGD(TAG, "Loaded saved settings: %s", save.ssid);
ESP_LOGD(TAG, "Loaded settings: %s", save.ssid);
WiFiAP sta{};
sta.set_ssid(save.ssid);
@@ -84,11 +84,11 @@ void WiFiComponent::start() {
if (this->has_sta()) {
this->wifi_sta_pre_setup_();
if (this->output_power_.has_value() && !this->wifi_apply_output_power_(*this->output_power_)) {
ESP_LOGV(TAG, "Setting Output Power Option failed!");
ESP_LOGV(TAG, "Setting Output Power Option failed");
}
if (!this->wifi_apply_power_save_()) {
ESP_LOGV(TAG, "Setting Power Save Option failed!");
ESP_LOGV(TAG, "Setting Power Save Option failed");
}
if (this->fast_connect_) {
@@ -102,7 +102,7 @@ void WiFiComponent::start() {
} else if (this->has_ap()) {
this->setup_ap_config_();
if (this->output_power_.has_value() && !this->wifi_apply_output_power_(*this->output_power_)) {
ESP_LOGV(TAG, "Setting Output Power Option failed!");
ESP_LOGV(TAG, "Setting Output Power Option failed");
}
#ifdef USE_CAPTIVE_PORTAL
if (captive_portal::global_captive_portal != nullptr) {
@@ -181,7 +181,7 @@ void WiFiComponent::loop() {
#ifdef USE_WIFI_AP
if (this->has_ap() && !this->ap_setup_) {
if (this->ap_timeout_ != 0 && (now - this->last_connected_ > this->ap_timeout_)) {
ESP_LOGI(TAG, "Starting fallback AP!");
ESP_LOGI(TAG, "Starting fallback AP");
this->setup_ap_config_();
#ifdef USE_CAPTIVE_PORTAL
if (captive_portal::global_captive_portal != nullptr)
@@ -359,7 +359,7 @@ void WiFiComponent::start_connecting(const WiFiAP &ap, bool two) {
if (ap.get_channel().has_value()) {
ESP_LOGV(TAG, " Channel: %u", *ap.get_channel());
} else {
ESP_LOGV(TAG, " Channel: Not Set");
ESP_LOGV(TAG, " Channel not set");
}
if (ap.get_manual_ip().has_value()) {
ManualIP m = *ap.get_manual_ip();
@@ -372,7 +372,7 @@ void WiFiComponent::start_connecting(const WiFiAP &ap, bool two) {
#endif
if (!this->wifi_sta_connect_(ap)) {
ESP_LOGE(TAG, "wifi_sta_connect_ failed!");
ESP_LOGE(TAG, "wifi_sta_connect_ failed");
this->retry_connect();
return;
}
@@ -500,20 +500,20 @@ void WiFiComponent::start_scanning() {
void WiFiComponent::check_scanning_finished() {
if (!this->scan_done_) {
if (millis() - this->action_started_ > 30000) {
ESP_LOGE(TAG, "Scan timeout!");
ESP_LOGE(TAG, "Scan timeout");
this->retry_connect();
}
return;
}
this->scan_done_ = false;
ESP_LOGD(TAG, "Found networks:");
if (this->scan_result_.empty()) {
ESP_LOGD(TAG, " No network found!");
ESP_LOGW(TAG, "No networks found");
this->retry_connect();
return;
}
ESP_LOGD(TAG, "Found networks:");
for (auto &res : this->scan_result_) {
for (auto &ap : this->sta_) {
if (res.matches(ap)) {
@@ -561,7 +561,7 @@ void WiFiComponent::check_scanning_finished() {
}
if (!this->scan_result_[0].get_matches()) {
ESP_LOGW(TAG, "No matching network found!");
ESP_LOGW(TAG, "No matching network found");
this->retry_connect();
return;
}
@@ -619,7 +619,7 @@ void WiFiComponent::check_connecting_finished() {
if (status == WiFiSTAConnectStatus::CONNECTED) {
if (wifi_ssid().empty()) {
ESP_LOGW(TAG, "Incomplete connection.");
ESP_LOGW(TAG, "Connection incomplete");
this->retry_connect();
return;
}
@@ -663,7 +663,7 @@ void WiFiComponent::check_connecting_finished() {
}
if (this->error_from_callback_) {
ESP_LOGW(TAG, "Error while connecting to network.");
ESP_LOGW(TAG, "Connecting to network failed");
this->retry_connect();
return;
}
@@ -679,7 +679,7 @@ void WiFiComponent::check_connecting_finished() {
}
if (status == WiFiSTAConnectStatus::ERROR_CONNECT_FAILED) {
ESP_LOGW(TAG, "Connection failed. Check credentials");
ESP_LOGW(TAG, "Connecting to network failed");
this->retry_connect();
return;
}
@@ -700,7 +700,7 @@ void WiFiComponent::retry_connect() {
(this->num_retried_ > 3 || this->error_from_callback_)) {
if (this->num_retried_ > 5) {
// If retry failed for more than 5 times, let's restart STA
ESP_LOGW(TAG, "Restarting WiFi adapter");
ESP_LOGW(TAG, "Restarting adapter");
this->wifi_mode_(false, {});
delay(100); // NOLINT
this->num_retried_ = 0;
@@ -770,7 +770,7 @@ void WiFiComponent::load_fast_connect_settings_() {
this->selected_ap_.set_bssid(bssid);
this->selected_ap_.set_channel(fast_connect_save.channel);
ESP_LOGD(TAG, "Loaded saved fast_connect wifi settings");
ESP_LOGD(TAG, "Loaded fast_connect settings");
}
}
@@ -786,7 +786,7 @@ void WiFiComponent::save_fast_connect_settings_() {
this->fast_connect_pref_.save(&fast_connect_save);
ESP_LOGD(TAG, "Saved fast_connect wifi settings");
ESP_LOGD(TAG, "Saved fast_connect settings");
}
}

View File

@@ -78,14 +78,14 @@ bool WiFiComponent::wifi_mode_(optional<bool> sta, optional<bool> ap) {
return true;
if (set_sta && !current_sta) {
ESP_LOGV(TAG, "Enabling STA.");
ESP_LOGV(TAG, "Enabling STA");
} else if (!set_sta && current_sta) {
ESP_LOGV(TAG, "Disabling STA.");
ESP_LOGV(TAG, "Disabling STA");
}
if (set_ap && !current_ap) {
ESP_LOGV(TAG, "Enabling AP.");
ESP_LOGV(TAG, "Enabling AP");
} else if (!set_ap && current_ap) {
ESP_LOGV(TAG, "Disabling AP.");
ESP_LOGV(TAG, "Disabling AP");
}
bool ret = WiFiClass::mode(set_mode);
@@ -147,11 +147,11 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
wifi_config_t conf;
memset(&conf, 0, sizeof(conf));
if (ap.get_ssid().size() > sizeof(conf.sta.ssid)) {
ESP_LOGE(TAG, "SSID is too long");
ESP_LOGE(TAG, "SSID too long");
return false;
}
if (ap.get_password().size() > sizeof(conf.sta.password)) {
ESP_LOGE(TAG, "password is too long");
ESP_LOGE(TAG, "Password too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.sta.ssid), ap.get_ssid().c_str(), ap.get_ssid().size());
@@ -230,7 +230,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
EAPAuth eap = ap.get_eap().value();
err = esp_eap_client_set_identity((uint8_t *) eap.identity.c_str(), eap.identity.length());
if (err != ESP_OK) {
ESP_LOGV(TAG, "esp_eap_client_set_identity failed! %d", err);
ESP_LOGV(TAG, "esp_eap_client_set_identity failed: %d", err);
}
int ca_cert_len = strlen(eap.ca_cert);
int client_cert_len = strlen(eap.client_cert);
@@ -238,7 +238,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
if (ca_cert_len) {
err = esp_eap_client_set_ca_cert((uint8_t *) eap.ca_cert, ca_cert_len + 1);
if (err != ESP_OK) {
ESP_LOGV(TAG, "esp_eap_client_set_ca_cert failed! %d", err);
ESP_LOGV(TAG, "esp_eap_client_set_ca_cert failed: %d", err);
}
}
// workout what type of EAP this is
@@ -249,22 +249,22 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
(uint8_t *) eap.client_key, client_key_len + 1,
(uint8_t *) eap.password.c_str(), strlen(eap.password.c_str()));
if (err != ESP_OK) {
ESP_LOGV(TAG, "esp_eap_client_set_certificate_and_key failed! %d", err);
ESP_LOGV(TAG, "esp_eap_client_set_certificate_and_key failed: %d", err);
}
} else {
// in the absence of certs, assume this is username/password based
err = esp_eap_client_set_username((uint8_t *) eap.username.c_str(), eap.username.length());
if (err != ESP_OK) {
ESP_LOGV(TAG, "esp_eap_client_set_username failed! %d", err);
ESP_LOGV(TAG, "esp_eap_client_set_username failed: %d", err);
}
err = esp_eap_client_set_password((uint8_t *) eap.password.c_str(), eap.password.length());
if (err != ESP_OK) {
ESP_LOGV(TAG, "esp_eap_client_set_password failed! %d", err);
ESP_LOGV(TAG, "esp_eap_client_set_password failed: %d", err);
}
}
err = esp_wifi_sta_enterprise_enable();
if (err != ESP_OK) {
ESP_LOGV(TAG, "esp_wifi_sta_enterprise_enable failed! %d", err);
ESP_LOGV(TAG, "esp_wifi_sta_enterprise_enable failed: %d", err);
}
}
#endif // USE_WIFI_WPA2_EAP
@@ -319,7 +319,7 @@ bool WiFiComponent::wifi_sta_ip_config_(optional<ManualIP> manual_ip) {
if (dhcp_status != ESP_NETIF_DHCP_STARTED) {
err = esp_netif_dhcpc_start(s_sta_netif);
if (err != ESP_OK) {
ESP_LOGV(TAG, "Starting DHCP client failed! %d", err);
ESP_LOGV(TAG, "Starting DHCP client failed: %d", err);
}
return err == ESP_OK;
}
@@ -332,12 +332,12 @@ bool WiFiComponent::wifi_sta_ip_config_(optional<ManualIP> manual_ip) {
info.netmask = manual_ip->subnet;
err = esp_netif_dhcpc_stop(s_sta_netif);
if (err != ESP_OK && err != ESP_ERR_ESP_NETIF_DHCP_ALREADY_STOPPED) {
ESP_LOGV(TAG, "Stopping DHCP client failed! %s", esp_err_to_name(err));
ESP_LOGV(TAG, "Stopping DHCP client failed: %s", esp_err_to_name(err));
}
err = esp_netif_set_ip_info(s_sta_netif, &info);
if (err != ESP_OK) {
ESP_LOGV(TAG, "Setting manual IP info failed! %s", esp_err_to_name(err));
ESP_LOGV(TAG, "Setting manual IP info failed: %s", esp_err_to_name(err));
}
esp_netif_dns_info_t dns;
@@ -520,18 +520,18 @@ using esphome_wifi_event_info_t = arduino_event_info_t;
void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_wifi_event_info_t info) {
switch (event) {
case ESPHOME_EVENT_ID_WIFI_READY: {
ESP_LOGV(TAG, "Event: WiFi ready");
ESP_LOGV(TAG, "Ready");
break;
}
case ESPHOME_EVENT_ID_WIFI_SCAN_DONE: {
auto it = info.wifi_scan_done;
ESP_LOGV(TAG, "Event: WiFi Scan Done status=%u number=%u scan_id=%u", it.status, it.number, it.scan_id);
ESP_LOGV(TAG, "Scan done: status=%u number=%u scan_id=%u", it.status, it.number, it.scan_id);
this->wifi_scan_done_callback_();
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_START: {
ESP_LOGV(TAG, "Event: WiFi STA start");
ESP_LOGV(TAG, "STA start");
// apply hostname
s_sta_netif = esp_netif_get_handle_from_ifkey("WIFI_STA_DEF");
esp_err_t err = esp_netif_set_hostname(s_sta_netif, App.get_name().c_str());
@@ -541,7 +541,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_STOP: {
ESP_LOGV(TAG, "Event: WiFi STA stop");
ESP_LOGV(TAG, "STA stop");
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_CONNECTED: {
@@ -549,7 +549,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
char buf[33];
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
ESP_LOGV(TAG, "Event: Connected ssid='%s' bssid=" LOG_SECRET("%s") " channel=%u, authmode=%s", buf,
ESP_LOGV(TAG, "Connected ssid='%s' bssid=" LOG_SECRET("%s") " channel=%u, authmode=%s", buf,
format_mac_addr(it.bssid).c_str(), it.channel, get_auth_mode_str(it.authmode));
#if USE_NETWORK_IPV6
this->set_timeout(100, [] { WiFi.enableIPv6(); });
@@ -563,9 +563,9 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
if (it.reason == WIFI_REASON_NO_AP_FOUND) {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
ESP_LOGW(TAG, "Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
} else {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
ESP_LOGW(TAG, "Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
format_mac_addr(it.bssid).c_str(), get_disconnect_reason_str(it.reason));
}
@@ -585,8 +585,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
}
case ESPHOME_EVENT_ID_WIFI_STA_AUTHMODE_CHANGE: {
auto it = info.wifi_sta_authmode_change;
ESP_LOGV(TAG, "Event: Authmode Change old=%s new=%s", get_auth_mode_str(it.old_mode),
get_auth_mode_str(it.new_mode));
ESP_LOGV(TAG, "Authmode Change old=%s new=%s", get_auth_mode_str(it.old_mode), get_auth_mode_str(it.new_mode));
// Mitigate CVE-2020-12638
// https://lbsfilm.at/blog/wpa2-authenticationmode-downgrade-in-espressif-microprocessors
if (it.old_mode != WIFI_AUTH_OPEN && it.new_mode == WIFI_AUTH_OPEN) {
@@ -603,8 +602,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
}
case ESPHOME_EVENT_ID_WIFI_STA_GOT_IP: {
auto it = info.got_ip.ip_info;
ESP_LOGV(TAG, "Event: Got IP static_ip=%s gateway=%s", format_ip4_addr(it.ip).c_str(),
format_ip4_addr(it.gw).c_str());
ESP_LOGV(TAG, "static_ip=%s gateway=%s", format_ip4_addr(it.ip).c_str(), format_ip4_addr(it.gw).c_str());
this->got_ipv4_address_ = true;
#if USE_NETWORK_IPV6
s_sta_connecting = this->num_ipv6_addresses_ < USE_NETWORK_MIN_IPV6_ADDR_COUNT;
@@ -616,44 +614,44 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
#if USE_NETWORK_IPV6
case ESPHOME_EVENT_ID_WIFI_STA_GOT_IP6: {
auto it = info.got_ip6.ip6_info;
ESP_LOGV(TAG, "Got IPv6 address=" IPV6STR, IPV62STR(it.ip));
ESP_LOGV(TAG, "IPv6 address=" IPV6STR, IPV62STR(it.ip));
this->num_ipv6_addresses_++;
s_sta_connecting = !(this->got_ipv4_address_ & (this->num_ipv6_addresses_ >= USE_NETWORK_MIN_IPV6_ADDR_COUNT));
break;
}
#endif /* USE_NETWORK_IPV6 */
case ESPHOME_EVENT_ID_WIFI_STA_LOST_IP: {
ESP_LOGV(TAG, "Event: Lost IP");
ESP_LOGV(TAG, "Lost IP");
this->got_ipv4_address_ = false;
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_START: {
ESP_LOGV(TAG, "Event: WiFi AP start");
ESP_LOGV(TAG, "AP start");
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STOP: {
ESP_LOGV(TAG, "Event: WiFi AP stop");
ESP_LOGV(TAG, "AP stop");
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STACONNECTED: {
auto it = info.wifi_sta_connected;
auto &mac = it.bssid;
ESP_LOGV(TAG, "Event: AP client connected MAC=%s", format_mac_addr(mac).c_str());
ESP_LOGV(TAG, "AP client connected MAC=%s", format_mac_addr(mac).c_str());
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STADISCONNECTED: {
auto it = info.wifi_sta_disconnected;
auto &mac = it.bssid;
ESP_LOGV(TAG, "Event: AP client disconnected MAC=%s", format_mac_addr(mac).c_str());
ESP_LOGV(TAG, "AP client disconnected MAC=%s", format_mac_addr(mac).c_str());
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STAIPASSIGNED: {
ESP_LOGV(TAG, "Event: AP client assigned IP");
ESP_LOGV(TAG, "AP client assigned IP");
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_PROBEREQRECVED: {
auto it = info.wifi_ap_probereqrecved;
ESP_LOGVV(TAG, "Event: AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
ESP_LOGVV(TAG, "AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
break;
}
default:
@@ -685,7 +683,7 @@ bool WiFiComponent::wifi_scan_start_(bool passive) {
// need to use WiFi because of WiFiScanClass allocations :(
int16_t err = WiFi.scanNetworks(true, true, passive, 200);
if (err != WIFI_SCAN_RUNNING) {
ESP_LOGV(TAG, "WiFi.scanNetworks failed! %d", err);
ESP_LOGV(TAG, "WiFi.scanNetworks failed: %d", err);
return false;
}
@@ -741,7 +739,7 @@ bool WiFiComponent::wifi_ap_ip_config_(optional<ManualIP> manual_ip) {
err = esp_netif_set_ip_info(s_ap_netif, &info);
if (err != ESP_OK) {
ESP_LOGE(TAG, "esp_netif_set_ip_info failed! %d", err);
ESP_LOGE(TAG, "esp_netif_set_ip_info failed: %d", err);
return false;
}
@@ -757,14 +755,14 @@ bool WiFiComponent::wifi_ap_ip_config_(optional<ManualIP> manual_ip) {
err = esp_netif_dhcps_option(s_ap_netif, ESP_NETIF_OP_SET, ESP_NETIF_REQUESTED_IP_ADDRESS, &lease, sizeof(lease));
if (err != ESP_OK) {
ESP_LOGE(TAG, "esp_netif_dhcps_option failed! %d", err);
ESP_LOGE(TAG, "esp_netif_dhcps_option failed: %d", err);
return false;
}
err = esp_netif_dhcps_start(s_ap_netif);
if (err != ESP_OK) {
ESP_LOGE(TAG, "esp_netif_dhcps_start failed! %d", err);
ESP_LOGE(TAG, "esp_netif_dhcps_start failed: %d", err);
return false;
}
@@ -779,7 +777,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
wifi_config_t conf;
memset(&conf, 0, sizeof(conf));
if (ap.get_ssid().size() > sizeof(conf.ap.ssid)) {
ESP_LOGE(TAG, "AP SSID is too long");
ESP_LOGE(TAG, "AP SSID too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.ap.ssid), ap.get_ssid().c_str(), ap.get_ssid().size());
@@ -794,7 +792,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
} else {
conf.ap.authmode = WIFI_AUTH_WPA2_PSK;
if (ap.get_password().size() > sizeof(conf.ap.password)) {
ESP_LOGE(TAG, "AP password is too long");
ESP_LOGE(TAG, "AP password too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.ap.password), ap.get_password().c_str(), ap.get_password().size());
@@ -805,14 +803,14 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
esp_err_t err = esp_wifi_set_config(WIFI_IF_AP, &conf);
if (err != ESP_OK) {
ESP_LOGV(TAG, "esp_wifi_set_config failed! %d", err);
ESP_LOGV(TAG, "esp_wifi_set_config failed: %d", err);
return false;
}
yield();
if (!this->wifi_ap_ip_config_(ap.get_manual_ip())) {
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed!");
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed");
return false;
}

View File

@@ -59,17 +59,17 @@ bool WiFiComponent::wifi_mode_(optional<bool> sta, optional<bool> ap) {
return true;
if (target_sta && !current_sta) {
ESP_LOGV(TAG, "Enabling STA.");
ESP_LOGV(TAG, "Enabling STA");
} else if (!target_sta && current_sta) {
ESP_LOGV(TAG, "Disabling STA.");
ESP_LOGV(TAG, "Disabling STA");
// Stop DHCP client when disabling STA
// See https://github.com/esp8266/Arduino/pull/5703
wifi_station_dhcpc_stop();
}
if (target_ap && !current_ap) {
ESP_LOGV(TAG, "Enabling AP.");
ESP_LOGV(TAG, "Enabling AP");
} else if (!target_ap && current_ap) {
ESP_LOGV(TAG, "Disabling AP.");
ESP_LOGV(TAG, "Disabling AP");
}
ETS_UART_INTR_DISABLE();
@@ -82,7 +82,7 @@ bool WiFiComponent::wifi_mode_(optional<bool> sta, optional<bool> ap) {
ETS_UART_INTR_ENABLE();
if (!ret) {
ESP_LOGW(TAG, "Setting WiFi mode failed!");
ESP_LOGW(TAG, "Set mode failed");
}
return ret;
@@ -133,7 +133,7 @@ bool WiFiComponent::wifi_sta_ip_config_(optional<ManualIP> manual_ip) {
if (dhcp_status != DHCP_STARTED) {
bool ret = wifi_station_dhcpc_start();
if (!ret) {
ESP_LOGV(TAG, "Starting DHCP client failed!");
ESP_LOGV(TAG, "Starting DHCP client failed");
}
return ret;
}
@@ -157,13 +157,13 @@ bool WiFiComponent::wifi_sta_ip_config_(optional<ManualIP> manual_ip) {
if (dhcp_status == DHCP_STARTED) {
bool dhcp_stop_ret = wifi_station_dhcpc_stop();
if (!dhcp_stop_ret) {
ESP_LOGV(TAG, "Stopping DHCP client failed!");
ESP_LOGV(TAG, "Stopping DHCP client failed");
ret = false;
}
}
bool wifi_set_info_ret = wifi_set_ip_info(STATION_IF, &info);
if (!wifi_set_info_ret) {
ESP_LOGV(TAG, "Setting manual IP info failed!");
ESP_LOGV(TAG, "Set manual IP info failed");
ret = false;
}
@@ -202,7 +202,7 @@ bool WiFiComponent::wifi_apply_hostname_() {
const std::string &hostname = App.get_name();
bool ret = wifi_station_set_hostname(const_cast<char *>(hostname.c_str()));
if (!ret) {
ESP_LOGV(TAG, "Setting WiFi Hostname failed!");
ESP_LOGV(TAG, "Set hostname failed");
}
// inform dhcp server of hostname change using dhcp_renew()
@@ -237,11 +237,11 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
struct station_config conf {};
memset(&conf, 0, sizeof(conf));
if (ap.get_ssid().size() > sizeof(conf.ssid)) {
ESP_LOGE(TAG, "SSID is too long");
ESP_LOGE(TAG, "SSID too long");
return false;
}
if (ap.get_password().size() > sizeof(conf.password)) {
ESP_LOGE(TAG, "password is too long");
ESP_LOGE(TAG, "Password too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.ssid), ap.get_ssid().c_str(), ap.get_ssid().size());
@@ -269,7 +269,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
ETS_UART_INTR_ENABLE();
if (!ret) {
ESP_LOGV(TAG, "Setting WiFi Station config failed!");
ESP_LOGV(TAG, "Set Station config failed");
return false;
}
@@ -284,7 +284,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
EAPAuth eap = ap.get_eap().value();
ret = wifi_station_set_enterprise_identity((uint8_t *) eap.identity.c_str(), eap.identity.length());
if (ret) {
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_identity failed! %d", ret);
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_identity failed: %d", ret);
}
int ca_cert_len = strlen(eap.ca_cert);
int client_cert_len = strlen(eap.client_cert);
@@ -292,7 +292,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
if (ca_cert_len) {
ret = wifi_station_set_enterprise_ca_cert((uint8_t *) eap.ca_cert, ca_cert_len + 1);
if (ret) {
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_ca_cert failed! %d", ret);
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_ca_cert failed: %d", ret);
}
}
// workout what type of EAP this is
@@ -303,22 +303,22 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
(uint8_t *) eap.client_key, client_key_len + 1,
(uint8_t *) eap.password.c_str(), strlen(eap.password.c_str()));
if (ret) {
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_cert_key failed! %d", ret);
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_cert_key failed: %d", ret);
}
} else {
// in the absence of certs, assume this is username/password based
ret = wifi_station_set_enterprise_username((uint8_t *) eap.username.c_str(), eap.username.length());
if (ret) {
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_username failed! %d", ret);
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_username failed: %d", ret);
}
ret = wifi_station_set_enterprise_password((uint8_t *) eap.password.c_str(), eap.password.length());
if (ret) {
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_password failed! %d", ret);
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_set_password failed: %d", ret);
}
}
ret = wifi_station_set_wpa2_enterprise_auth(true);
if (ret) {
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_enable failed! %d", ret);
ESP_LOGV(TAG, "esp_wifi_sta_wpa2_ent_enable failed: %d", ret);
}
}
#endif // USE_WIFI_WPA2_EAP
@@ -337,7 +337,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
ret = wifi_station_connect();
ETS_UART_INTR_ENABLE();
if (!ret) {
ESP_LOGV(TAG, "wifi_station_connect failed!");
ESP_LOGV(TAG, "wifi_station_connect failed");
return false;
}
@@ -359,7 +359,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
if (ap.get_channel().has_value()) {
ret = wifi_set_channel(*ap.get_channel());
if (!ret) {
ESP_LOGV(TAG, "wifi_set_channel failed!");
ESP_LOGV(TAG, "wifi_set_channel failed");
return false;
}
}
@@ -496,8 +496,7 @@ void WiFiComponent::wifi_event_callback(System_Event_t *event) {
char buf[33];
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
ESP_LOGV(TAG, "Event: Connected ssid='%s' bssid=%s channel=%u", buf, format_mac_addr(it.bssid).c_str(),
it.channel);
ESP_LOGV(TAG, "Connected ssid='%s' bssid=%s channel=%u", buf, format_mac_addr(it.bssid).c_str(), it.channel);
s_sta_connected = true;
break;
}
@@ -507,10 +506,10 @@ void WiFiComponent::wifi_event_callback(System_Event_t *event) {
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
if (it.reason == REASON_NO_AP_FOUND) {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
ESP_LOGW(TAG, "Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
s_sta_connect_not_found = true;
} else {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
ESP_LOGW(TAG, "Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
format_mac_addr(it.bssid).c_str(), LOG_STR_ARG(get_disconnect_reason_str(it.reason)));
s_sta_connect_error = true;
}
@@ -520,7 +519,7 @@ void WiFiComponent::wifi_event_callback(System_Event_t *event) {
}
case EVENT_STAMODE_AUTHMODE_CHANGE: {
auto it = event->event_info.auth_change;
ESP_LOGV(TAG, "Event: Changed AuthMode old=%s new=%s", LOG_STR_ARG(get_auth_mode_str(it.old_mode)),
ESP_LOGV(TAG, "Changed Authmode old=%s new=%s", LOG_STR_ARG(get_auth_mode_str(it.old_mode)),
LOG_STR_ARG(get_auth_mode_str(it.new_mode)));
// Mitigate CVE-2020-12638
// https://lbsfilm.at/blog/wpa2-authenticationmode-downgrade-in-espressif-microprocessors
@@ -535,40 +534,40 @@ void WiFiComponent::wifi_event_callback(System_Event_t *event) {
}
case EVENT_STAMODE_GOT_IP: {
auto it = event->event_info.got_ip;
ESP_LOGV(TAG, "Event: Got IP static_ip=%s gateway=%s netmask=%s", format_ip_addr(it.ip).c_str(),
format_ip_addr(it.gw).c_str(), format_ip_addr(it.mask).c_str());
ESP_LOGV(TAG, "static_ip=%s gateway=%s netmask=%s", format_ip_addr(it.ip).c_str(), format_ip_addr(it.gw).c_str(),
format_ip_addr(it.mask).c_str());
s_sta_got_ip = true;
break;
}
case EVENT_STAMODE_DHCP_TIMEOUT: {
ESP_LOGW(TAG, "Event: Getting IP address timeout");
ESP_LOGW(TAG, "DHCP request timeout");
break;
}
case EVENT_SOFTAPMODE_STACONNECTED: {
auto it = event->event_info.sta_connected;
ESP_LOGV(TAG, "Event: AP client connected MAC=%s aid=%u", format_mac_addr(it.mac).c_str(), it.aid);
ESP_LOGV(TAG, "AP client connected MAC=%s aid=%u", format_mac_addr(it.mac).c_str(), it.aid);
break;
}
case EVENT_SOFTAPMODE_STADISCONNECTED: {
auto it = event->event_info.sta_disconnected;
ESP_LOGV(TAG, "Event: AP client disconnected MAC=%s aid=%u", format_mac_addr(it.mac).c_str(), it.aid);
ESP_LOGV(TAG, "AP client disconnected MAC=%s aid=%u", format_mac_addr(it.mac).c_str(), it.aid);
break;
}
case EVENT_SOFTAPMODE_PROBEREQRECVED: {
auto it = event->event_info.ap_probereqrecved;
ESP_LOGVV(TAG, "Event: AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
ESP_LOGVV(TAG, "AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
break;
}
#if USE_ARDUINO_VERSION_CODE >= VERSION_CODE(2, 4, 0)
case EVENT_OPMODE_CHANGED: {
auto it = event->event_info.opmode_changed;
ESP_LOGV(TAG, "Event: Changed Mode old=%s new=%s", LOG_STR_ARG(get_op_mode_str(it.old_opmode)),
ESP_LOGV(TAG, "Changed Mode old=%s new=%s", LOG_STR_ARG(get_op_mode_str(it.old_opmode)),
LOG_STR_ARG(get_op_mode_str(it.new_opmode)));
break;
}
case EVENT_SOFTAPMODE_DISTRIBUTE_STA_IP: {
auto it = event->event_info.distribute_sta_ip;
ESP_LOGV(TAG, "Event: AP Distribute Station IP MAC=%s IP=%s aid=%u", format_mac_addr(it.mac).c_str(),
ESP_LOGV(TAG, "AP Distribute Station IP MAC=%s IP=%s aid=%u", format_mac_addr(it.mac).c_str(),
format_ip_addr(it.ip).c_str(), it.aid);
break;
}
@@ -600,7 +599,7 @@ bool WiFiComponent::wifi_sta_pre_setup_() {
ETS_UART_INTR_ENABLE();
if (!ret1 || !ret2) {
ESP_LOGV(TAG, "Disabling Auto-Connect failed!");
ESP_LOGV(TAG, "Disabling Auto-Connect failed");
}
delay(10);
@@ -666,7 +665,7 @@ bool WiFiComponent::wifi_scan_start_(bool passive) {
first_scan = false;
bool ret = wifi_station_scan(&config, &WiFiComponent::s_wifi_scan_done_callback);
if (!ret) {
ESP_LOGV(TAG, "wifi_station_scan failed!");
ESP_LOGV(TAG, "wifi_station_scan failed");
return false;
}
@@ -692,7 +691,7 @@ void WiFiComponent::wifi_scan_done_callback_(void *arg, STATUS status) {
this->scan_result_.clear();
if (status != OK) {
ESP_LOGV(TAG, "Scan failed! %d", status);
ESP_LOGV(TAG, "Scan failed: %d", status);
this->retry_connect();
return;
}
@@ -725,12 +724,12 @@ bool WiFiComponent::wifi_ap_ip_config_(optional<ManualIP> manual_ip) {
if (wifi_softap_dhcps_status() == DHCP_STARTED) {
if (!wifi_softap_dhcps_stop()) {
ESP_LOGW(TAG, "Stopping DHCP server failed!");
ESP_LOGW(TAG, "Stopping DHCP server failed");
}
}
if (!wifi_set_ip_info(SOFTAP_IF, &info)) {
ESP_LOGE(TAG, "Setting SoftAP info failed!");
ESP_LOGE(TAG, "Set SoftAP info failed");
return false;
}
@@ -748,13 +747,13 @@ bool WiFiComponent::wifi_ap_ip_config_(optional<ManualIP> manual_ip) {
lease.end_ip = start_address;
ESP_LOGV(TAG, "DHCP server IP lease end: %s", start_address.str().c_str());
if (!wifi_softap_set_dhcps_lease(&lease)) {
ESP_LOGE(TAG, "Setting SoftAP DHCP lease failed!");
ESP_LOGE(TAG, "Set SoftAP DHCP lease failed");
return false;
}
// lease time 1440 minutes (=24 hours)
if (!wifi_softap_set_dhcps_lease_time(1440)) {
ESP_LOGE(TAG, "Setting SoftAP DHCP lease time failed!");
ESP_LOGE(TAG, "Set SoftAP DHCP lease time failed");
return false;
}
@@ -764,13 +763,13 @@ bool WiFiComponent::wifi_ap_ip_config_(optional<ManualIP> manual_ip) {
uint8_t mode = 1;
// bit0, 1 enables router information from ESP8266 SoftAP DHCP server.
if (!wifi_softap_set_dhcps_offer_option(OFFER_ROUTER, &mode)) {
ESP_LOGE(TAG, "wifi_softap_set_dhcps_offer_option failed!");
ESP_LOGE(TAG, "wifi_softap_set_dhcps_offer_option failed");
return false;
}
#endif
if (!wifi_softap_dhcps_start()) {
ESP_LOGE(TAG, "Starting SoftAP DHCPS failed!");
ESP_LOGE(TAG, "Starting SoftAP DHCPS failed");
return false;
}
@@ -784,7 +783,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
struct softap_config conf {};
if (ap.get_ssid().size() > sizeof(conf.ssid)) {
ESP_LOGE(TAG, "AP SSID is too long");
ESP_LOGE(TAG, "AP SSID too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.ssid), ap.get_ssid().c_str(), ap.get_ssid().size());
@@ -800,7 +799,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
} else {
conf.authmode = AUTH_WPA2_PSK;
if (ap.get_password().size() > sizeof(conf.password)) {
ESP_LOGE(TAG, "AP password is too long");
ESP_LOGE(TAG, "AP password too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.password), ap.get_password().c_str(), ap.get_password().size());
@@ -811,12 +810,12 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
ETS_UART_INTR_ENABLE();
if (!ret) {
ESP_LOGV(TAG, "wifi_softap_set_config_current failed!");
ESP_LOGV(TAG, "wifi_softap_set_config_current failed");
return false;
}
if (!this->wifi_ap_ip_config_(ap.get_manual_ip())) {
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed!");
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed");
return false;
}

View File

@@ -219,14 +219,14 @@ bool WiFiComponent::wifi_mode_(optional<bool> sta, optional<bool> ap) {
return true;
if (set_sta && !current_sta) {
ESP_LOGV(TAG, "Enabling STA.");
ESP_LOGV(TAG, "Enabling STA");
} else if (!set_sta && current_sta) {
ESP_LOGV(TAG, "Disabling STA.");
ESP_LOGV(TAG, "Disabling STA");
}
if (set_ap && !current_ap) {
ESP_LOGV(TAG, "Enabling AP.");
ESP_LOGV(TAG, "Enabling AP");
} else if (!set_ap && current_ap) {
ESP_LOGV(TAG, "Disabling AP.");
ESP_LOGV(TAG, "Disabling AP");
}
if (set_mode == WIFI_MODE_NULL && s_wifi_started) {
@@ -290,11 +290,11 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
wifi_config_t conf;
memset(&conf, 0, sizeof(conf));
if (ap.get_ssid().size() > sizeof(conf.sta.ssid)) {
ESP_LOGE(TAG, "SSID is too long");
ESP_LOGE(TAG, "SSID too long");
return false;
}
if (ap.get_password().size() > sizeof(conf.sta.password)) {
ESP_LOGE(TAG, "password is too long");
ESP_LOGE(TAG, "Password too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.sta.ssid), ap.get_ssid().c_str(), ap.get_ssid().size());
@@ -490,7 +490,7 @@ bool WiFiComponent::wifi_sta_ip_config_(optional<ManualIP> manual_ip) {
if (dhcp_status != ESP_NETIF_DHCP_STARTED) {
err = esp_netif_dhcpc_start(s_sta_netif);
if (err != ESP_OK) {
ESP_LOGV(TAG, "Starting DHCP client failed! %d", err);
ESP_LOGV(TAG, "Starting DHCP client failed: %d", err);
}
return err == ESP_OK;
}
@@ -503,12 +503,12 @@ bool WiFiComponent::wifi_sta_ip_config_(optional<ManualIP> manual_ip) {
info.netmask = manual_ip->subnet;
err = esp_netif_dhcpc_stop(s_sta_netif);
if (err != ESP_OK && err != ESP_ERR_ESP_NETIF_DHCP_ALREADY_STOPPED) {
ESP_LOGV(TAG, "Stopping DHCP client failed! %s", esp_err_to_name(err));
ESP_LOGV(TAG, "Stopping DHCP client failed: %s", esp_err_to_name(err));
}
err = esp_netif_set_ip_info(s_sta_netif, &info);
if (err != ESP_OK) {
ESP_LOGV(TAG, "Setting manual IP info failed! %s", esp_err_to_name(err));
ESP_LOGV(TAG, "Setting manual IP info failed: %s", esp_err_to_name(err));
}
esp_netif_dns_info_t dns;
@@ -665,7 +665,7 @@ void WiFiComponent::wifi_loop_() {
void WiFiComponent::wifi_process_event_(IDFWiFiEvent *data) {
esp_err_t err;
if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_STA_START) {
ESP_LOGV(TAG, "Event: WiFi STA start");
ESP_LOGV(TAG, "STA start");
// apply hostname
err = esp_netif_set_hostname(s_sta_netif, App.get_name().c_str());
if (err != ERR_OK) {
@@ -677,13 +677,12 @@ void WiFiComponent::wifi_process_event_(IDFWiFiEvent *data) {
wifi_apply_power_save_();
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_STA_STOP) {
ESP_LOGV(TAG, "Event: WiFi STA stop");
ESP_LOGV(TAG, "STA stop");
s_sta_started = false;
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_STA_AUTHMODE_CHANGE) {
const auto &it = data->data.sta_authmode_change;
ESP_LOGV(TAG, "Event: Authmode Change old=%s new=%s", get_auth_mode_str(it.old_mode),
get_auth_mode_str(it.new_mode));
ESP_LOGV(TAG, "Authmode Change old=%s new=%s", get_auth_mode_str(it.old_mode), get_auth_mode_str(it.new_mode));
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_STA_CONNECTED) {
const auto &it = data->data.sta_connected;
@@ -691,7 +690,7 @@ void WiFiComponent::wifi_process_event_(IDFWiFiEvent *data) {
assert(it.ssid_len <= 32);
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
ESP_LOGV(TAG, "Event: Connected ssid='%s' bssid=" LOG_SECRET("%s") " channel=%u, authmode=%s", buf,
ESP_LOGV(TAG, "Connected ssid='%s' bssid=" LOG_SECRET("%s") " channel=%u, authmode=%s", buf,
format_mac_addr(it.bssid).c_str(), it.channel, get_auth_mode_str(it.authmode));
s_sta_connected = true;
@@ -702,13 +701,13 @@ void WiFiComponent::wifi_process_event_(IDFWiFiEvent *data) {
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
if (it.reason == WIFI_REASON_NO_AP_FOUND) {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
ESP_LOGW(TAG, "Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
s_sta_connect_not_found = true;
} else if (it.reason == WIFI_REASON_ROAMING) {
ESP_LOGI(TAG, "Event: Disconnected ssid='%s' reason='Station Roaming'", buf);
ESP_LOGI(TAG, "Disconnected ssid='%s' reason='Station Roaming'", buf);
return;
} else {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
ESP_LOGW(TAG, "Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
format_mac_addr(it.bssid).c_str(), get_disconnect_reason_str(it.reason));
s_sta_connect_error = true;
}
@@ -721,24 +720,24 @@ void WiFiComponent::wifi_process_event_(IDFWiFiEvent *data) {
#if USE_NETWORK_IPV6
esp_netif_create_ip6_linklocal(s_sta_netif);
#endif /* USE_NETWORK_IPV6 */
ESP_LOGV(TAG, "Event: Got IP static_ip=%s gateway=%s", format_ip4_addr(it.ip_info.ip).c_str(),
ESP_LOGV(TAG, "static_ip=%s gateway=%s", format_ip4_addr(it.ip_info.ip).c_str(),
format_ip4_addr(it.ip_info.gw).c_str());
this->got_ipv4_address_ = true;
#if USE_NETWORK_IPV6
} else if (data->event_base == IP_EVENT && data->event_id == IP_EVENT_GOT_IP6) {
const auto &it = data->data.ip_got_ip6;
ESP_LOGV(TAG, "Event: Got IPv6 address=%s", format_ip6_addr(it.ip6_info.ip).c_str());
ESP_LOGV(TAG, "IPv6 address=%s", format_ip6_addr(it.ip6_info.ip).c_str());
this->num_ipv6_addresses_++;
#endif /* USE_NETWORK_IPV6 */
} else if (data->event_base == IP_EVENT && data->event_id == IP_EVENT_STA_LOST_IP) {
ESP_LOGV(TAG, "Event: Lost IP");
ESP_LOGV(TAG, "Lost IP");
this->got_ipv4_address_ = false;
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_SCAN_DONE) {
const auto &it = data->data.sta_scan_done;
ESP_LOGV(TAG, "Event: WiFi Scan Done status=%" PRIu32 " number=%u scan_id=%u", it.status, it.number, it.scan_id);
ESP_LOGV(TAG, "Scan done: status=%" PRIu32 " number=%u scan_id=%u", it.status, it.number, it.scan_id);
scan_result_.clear();
this->scan_done_ = true;
@@ -772,28 +771,28 @@ void WiFiComponent::wifi_process_event_(IDFWiFiEvent *data) {
}
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_AP_START) {
ESP_LOGV(TAG, "Event: WiFi AP start");
ESP_LOGV(TAG, "AP start");
s_ap_started = true;
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_AP_STOP) {
ESP_LOGV(TAG, "Event: WiFi AP stop");
ESP_LOGV(TAG, "AP stop");
s_ap_started = false;
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_AP_PROBEREQRECVED) {
const auto &it = data->data.ap_probe_req_rx;
ESP_LOGVV(TAG, "Event: AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
ESP_LOGVV(TAG, "AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_AP_STACONNECTED) {
const auto &it = data->data.ap_staconnected;
ESP_LOGV(TAG, "Event: AP client connected MAC=%s", format_mac_addr(it.mac).c_str());
ESP_LOGV(TAG, "AP client connected MAC=%s", format_mac_addr(it.mac).c_str());
} else if (data->event_base == WIFI_EVENT && data->event_id == WIFI_EVENT_AP_STADISCONNECTED) {
const auto &it = data->data.ap_stadisconnected;
ESP_LOGV(TAG, "Event: AP client disconnected MAC=%s", format_mac_addr(it.mac).c_str());
ESP_LOGV(TAG, "AP client disconnected MAC=%s", format_mac_addr(it.mac).c_str());
} else if (data->event_base == IP_EVENT && data->event_id == IP_EVENT_AP_STAIPASSIGNED) {
const auto &it = data->data.ip_ap_staipassigned;
ESP_LOGV(TAG, "Event: AP client assigned IP %s", format_ip4_addr(it.ip).c_str());
ESP_LOGV(TAG, "AP client assigned IP %s", format_ip4_addr(it.ip).c_str());
}
}
@@ -873,7 +872,7 @@ bool WiFiComponent::wifi_ap_ip_config_(optional<ManualIP> manual_ip) {
err = esp_netif_set_ip_info(s_ap_netif, &info);
if (err != ESP_OK) {
ESP_LOGE(TAG, "esp_netif_set_ip_info failed! %d", err);
ESP_LOGE(TAG, "esp_netif_set_ip_info failed: %d", err);
return false;
}
@@ -889,14 +888,14 @@ bool WiFiComponent::wifi_ap_ip_config_(optional<ManualIP> manual_ip) {
err = esp_netif_dhcps_option(s_ap_netif, ESP_NETIF_OP_SET, ESP_NETIF_REQUESTED_IP_ADDRESS, &lease, sizeof(lease));
if (err != ESP_OK) {
ESP_LOGE(TAG, "esp_netif_dhcps_option failed! %d", err);
ESP_LOGE(TAG, "esp_netif_dhcps_option failed: %d", err);
return false;
}
err = esp_netif_dhcps_start(s_ap_netif);
if (err != ESP_OK) {
ESP_LOGE(TAG, "esp_netif_dhcps_start failed! %d", err);
ESP_LOGE(TAG, "esp_netif_dhcps_start failed: %d", err);
return false;
}
@@ -911,7 +910,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
wifi_config_t conf;
memset(&conf, 0, sizeof(conf));
if (ap.get_ssid().size() > sizeof(conf.ap.ssid)) {
ESP_LOGE(TAG, "AP SSID is too long");
ESP_LOGE(TAG, "AP SSID too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.ap.ssid), ap.get_ssid().c_str(), ap.get_ssid().size());
@@ -926,7 +925,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
} else {
conf.ap.authmode = WIFI_AUTH_WPA2_PSK;
if (ap.get_password().size() > sizeof(conf.ap.password)) {
ESP_LOGE(TAG, "AP password is too long");
ESP_LOGE(TAG, "AP password too long");
return false;
}
memcpy(reinterpret_cast<char *>(conf.ap.password), ap.get_password().c_str(), ap.get_password().size());
@@ -937,12 +936,12 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
esp_err_t err = esp_wifi_set_config(WIFI_IF_AP, &conf);
if (err != ESP_OK) {
ESP_LOGE(TAG, "esp_wifi_set_config failed! %d", err);
ESP_LOGE(TAG, "esp_wifi_set_config failed: %d", err);
return false;
}
if (!this->wifi_ap_ip_config_(ap.get_manual_ip())) {
ESP_LOGE(TAG, "wifi_ap_ip_config_ failed!");
ESP_LOGE(TAG, "wifi_ap_ip_config_ failed:");
return false;
}

View File

@@ -32,14 +32,14 @@ bool WiFiComponent::wifi_mode_(optional<bool> sta, optional<bool> ap) {
return true;
if (enable_sta && !current_sta) {
ESP_LOGV(TAG, "Enabling STA.");
ESP_LOGV(TAG, "Enabling STA");
} else if (!enable_sta && current_sta) {
ESP_LOGV(TAG, "Disabling STA.");
ESP_LOGV(TAG, "Disabling STA");
}
if (enable_ap && !current_ap) {
ESP_LOGV(TAG, "Enabling AP.");
ESP_LOGV(TAG, "Enabling AP");
} else if (!enable_ap && current_ap) {
ESP_LOGV(TAG, "Disabling AP.");
ESP_LOGV(TAG, "Disabling AP");
}
uint8_t mode = 0;
@@ -124,7 +124,7 @@ bool WiFiComponent::wifi_sta_connect_(const WiFiAP &ap) {
ap.get_channel().has_value() ? *ap.get_channel() : 0,
ap.get_bssid().has_value() ? ap.get_bssid()->data() : NULL);
if (status != WL_CONNECTED) {
ESP_LOGW(TAG, "esp_wifi_connect failed! %d", status);
ESP_LOGW(TAG, "esp_wifi_connect failed: %d", status);
return false;
}
@@ -256,23 +256,23 @@ using esphome_wifi_event_info_t = arduino_event_info_t;
void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_wifi_event_info_t info) {
switch (event) {
case ESPHOME_EVENT_ID_WIFI_READY: {
ESP_LOGV(TAG, "Event: WiFi ready");
ESP_LOGV(TAG, "Ready");
break;
}
case ESPHOME_EVENT_ID_WIFI_SCAN_DONE: {
auto it = info.wifi_scan_done;
ESP_LOGV(TAG, "Event: WiFi Scan Done status=%u number=%u scan_id=%u", it.status, it.number, it.scan_id);
ESP_LOGV(TAG, "Scan done: status=%u number=%u scan_id=%u", it.status, it.number, it.scan_id);
this->wifi_scan_done_callback_();
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_START: {
ESP_LOGV(TAG, "Event: WiFi STA start");
ESP_LOGV(TAG, "STA start");
WiFi.setHostname(App.get_name().c_str());
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_STOP: {
ESP_LOGV(TAG, "Event: WiFi STA stop");
ESP_LOGV(TAG, "STA stop");
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_CONNECTED: {
@@ -280,7 +280,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
char buf[33];
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
ESP_LOGV(TAG, "Event: Connected ssid='%s' bssid=" LOG_SECRET("%s") " channel=%u, authmode=%s", buf,
ESP_LOGV(TAG, "Connected ssid='%s' bssid=" LOG_SECRET("%s") " channel=%u, authmode=%s", buf,
format_mac_addr(it.bssid).c_str(), it.channel, get_auth_mode_str(it.authmode));
break;
@@ -291,9 +291,9 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
memcpy(buf, it.ssid, it.ssid_len);
buf[it.ssid_len] = '\0';
if (it.reason == WIFI_REASON_NO_AP_FOUND) {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
ESP_LOGW(TAG, "Disconnected ssid='%s' reason='Probe Request Unsuccessful'", buf);
} else {
ESP_LOGW(TAG, "Event: Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
ESP_LOGW(TAG, "Disconnected ssid='%s' bssid=" LOG_SECRET("%s") " reason='%s'", buf,
format_mac_addr(it.bssid).c_str(), get_disconnect_reason_str(it.reason));
}
@@ -310,8 +310,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
}
case ESPHOME_EVENT_ID_WIFI_STA_AUTHMODE_CHANGE: {
auto it = info.wifi_sta_authmode_change;
ESP_LOGV(TAG, "Event: Authmode Change old=%s new=%s", get_auth_mode_str(it.old_mode),
get_auth_mode_str(it.new_mode));
ESP_LOGV(TAG, "Authmode Change old=%s new=%s", get_auth_mode_str(it.old_mode), get_auth_mode_str(it.new_mode));
// Mitigate CVE-2020-12638
// https://lbsfilm.at/blog/wpa2-authenticationmode-downgrade-in-espressif-microprocessors
if (it.old_mode != WIFI_AUTH_OPEN && it.new_mode == WIFI_AUTH_OPEN) {
@@ -325,47 +324,47 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
}
case ESPHOME_EVENT_ID_WIFI_STA_GOT_IP: {
// auto it = info.got_ip.ip_info;
ESP_LOGV(TAG, "Event: Got IP static_ip=%s gateway=%s", format_ip4_addr(WiFi.localIP()).c_str(),
ESP_LOGV(TAG, "static_ip=%s gateway=%s", format_ip4_addr(WiFi.localIP()).c_str(),
format_ip4_addr(WiFi.gatewayIP()).c_str());
s_sta_connecting = false;
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_GOT_IP6: {
// auto it = info.got_ip.ip_info;
ESP_LOGV(TAG, "Event: Got IPv6");
ESP_LOGV(TAG, "Got IPv6");
break;
}
case ESPHOME_EVENT_ID_WIFI_STA_LOST_IP: {
ESP_LOGV(TAG, "Event: Lost IP");
ESP_LOGV(TAG, "Lost IP");
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_START: {
ESP_LOGV(TAG, "Event: WiFi AP start");
ESP_LOGV(TAG, "AP start");
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STOP: {
ESP_LOGV(TAG, "Event: WiFi AP stop");
ESP_LOGV(TAG, "AP stop");
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STACONNECTED: {
auto it = info.wifi_sta_connected;
auto &mac = it.bssid;
ESP_LOGV(TAG, "Event: AP client connected MAC=%s", format_mac_addr(mac).c_str());
ESP_LOGV(TAG, "AP client connected MAC=%s", format_mac_addr(mac).c_str());
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STADISCONNECTED: {
auto it = info.wifi_sta_disconnected;
auto &mac = it.bssid;
ESP_LOGV(TAG, "Event: AP client disconnected MAC=%s", format_mac_addr(mac).c_str());
ESP_LOGV(TAG, "AP client disconnected MAC=%s", format_mac_addr(mac).c_str());
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_STAIPASSIGNED: {
ESP_LOGV(TAG, "Event: AP client assigned IP");
ESP_LOGV(TAG, "AP client assigned IP");
break;
}
case ESPHOME_EVENT_ID_WIFI_AP_PROBEREQRECVED: {
auto it = info.wifi_ap_probereqrecved;
ESP_LOGVV(TAG, "Event: AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
ESP_LOGVV(TAG, "AP receive Probe Request MAC=%s RSSI=%d", format_mac_addr(it.mac).c_str(), it.rssi);
break;
}
default:
@@ -399,7 +398,7 @@ bool WiFiComponent::wifi_scan_start_(bool passive) {
// need to use WiFi because of WiFiScanClass allocations :(
int16_t err = WiFi.scanNetworks(true, true, passive, 200);
if (err != WIFI_SCAN_RUNNING) {
ESP_LOGV(TAG, "WiFi.scanNetworks failed! %d", err);
ESP_LOGV(TAG, "WiFi.scanNetworks failed: %d", err);
return false;
}
@@ -447,7 +446,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
return false;
if (!this->wifi_ap_ip_config_(ap.get_manual_ip())) {
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed!");
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed");
return false;
}

View File

@@ -134,7 +134,7 @@ bool WiFiComponent::wifi_scan_start_(bool passive) {
scan_options.scan_type = passive ? 1 : 0;
int err = cyw43_wifi_scan(&cyw43_state, &scan_options, nullptr, &s_wifi_scan_result);
if (err) {
ESP_LOGV(TAG, "cyw43_wifi_scan failed!");
ESP_LOGV(TAG, "cyw43_wifi_scan failed");
}
return err == 0;
return true;
@@ -162,7 +162,7 @@ bool WiFiComponent::wifi_start_ap_(const WiFiAP &ap) {
if (!this->wifi_mode_({}, true))
return false;
if (!this->wifi_ap_ip_config_(ap.get_manual_ip())) {
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed!");
ESP_LOGV(TAG, "wifi_ap_ip_config_ failed");
return false;
}
@@ -209,7 +209,7 @@ network::IPAddress WiFiComponent::wifi_dns_ip_(int num) {
void WiFiComponent::wifi_loop_() {
if (this->state_ == WIFI_COMPONENT_STATE_STA_SCANNING && !cyw43_wifi_scan_active(&cyw43_state)) {
this->scan_done_ = true;
ESP_LOGV(TAG, "Scan done!");
ESP_LOGV(TAG, "Scan done");
}
}

View File

@@ -7,12 +7,12 @@ namespace wifi_info {
static const char *const TAG = "wifi_info";
void IPAddressWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "WifiInfo IPAddress", this); }
void ScanResultsWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "WifiInfo Scan Results", this); }
void SSIDWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "WifiInfo SSID", this); }
void BSSIDWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "WifiInfo BSSID", this); }
void MacAddressWifiInfo::dump_config() { LOG_TEXT_SENSOR("", "WifiInfo Mac Address", this); }
void DNSAddressWifiInfo::dump_config() { LOG_TEXT_SENSOR("", "WifiInfo DNS Address", this); }
void IPAddressWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "IP Address", this); }
void ScanResultsWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "Scan Results", this); }
void SSIDWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "SSID", this); }
void BSSIDWiFiInfo::dump_config() { LOG_TEXT_SENSOR("", "BSSID", this); }
void MacAddressWifiInfo::dump_config() { LOG_TEXT_SENSOR("", "MAC Address", this); }
void DNSAddressWifiInfo::dump_config() { LOG_TEXT_SENSOR("", "DNS Address", this); }
} // namespace wifi_info
} // namespace esphome

View File

@@ -14,7 +14,7 @@ static const char *const TAG = "ring_buffer";
RingBuffer::~RingBuffer() {
if (this->handle_ != nullptr) {
vRingbufferDelete(this->handle_);
RAMAllocator<uint8_t> allocator(RAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
allocator.deallocate(this->storage_, this->size_);
}
}
@@ -24,7 +24,7 @@ std::unique_ptr<RingBuffer> RingBuffer::create(size_t len) {
rb->size_ = len;
RAMAllocator<uint8_t> allocator(RAMAllocator<uint8_t>::ALLOW_FAILURE);
RAMAllocator<uint8_t> allocator;
rb->storage_ = allocator.allocate(rb->size_);
if (rb->storage_ == nullptr) {
return nullptr;