1
0
mirror of https://github.com/esphome/esphome.git synced 2025-10-24 20:53:48 +01:00

Remove unnecessary ellipsis (#8964)

This commit is contained in:
Keith Burzinski
2025-06-03 15:46:10 -05:00
committed by GitHub
parent 8cbe2b41f6
commit 6675e99862
91 changed files with 179 additions and 181 deletions

View File

@@ -22,7 +22,7 @@ static const int ADC_MAX = (1 << SOC_ADC_RTC_MAX_BITWIDTH) - 1;
static const int ADC_HALF = (1 << SOC_ADC_RTC_MAX_BITWIDTH) >> 1;
void ADCSensor::setup() {
ESP_LOGCONFIG(TAG, "Running setup for '%s'...", this->get_name().c_str());
ESP_LOGCONFIG(TAG, "Running setup for '%s'", this->get_name().c_str());
if (this->channel1_ != ADC1_CHANNEL_MAX) {
adc1_config_width(ADC_WIDTH_MAX_SOC_BITS);

View File

@@ -17,7 +17,7 @@ namespace adc {
static const char *const TAG = "adc.esp8266";
void ADCSensor::setup() {
ESP_LOGCONFIG(TAG, "Running setup for '%s'...", this->get_name().c_str());
ESP_LOGCONFIG(TAG, "Running setup for '%s'", this->get_name().c_str());
#ifndef USE_ADC_SENSOR_VCC
this->pin_->setup();
#endif

View File

@@ -9,7 +9,7 @@ namespace adc {
static const char *const TAG = "adc.libretiny";
void ADCSensor::setup() {
ESP_LOGCONFIG(TAG, "Running setup for '%s'...", this->get_name().c_str());
ESP_LOGCONFIG(TAG, "Running setup for '%s'", this->get_name().c_str());
#ifndef USE_ADC_SENSOR_VCC
this->pin_->setup();
#endif // !USE_ADC_SENSOR_VCC

View File

@@ -14,7 +14,7 @@ namespace adc {
static const char *const TAG = "adc.rp2040";
void ADCSensor::setup() {
ESP_LOGCONFIG(TAG, "Running setup for '%s'...", this->get_name().c_str());
ESP_LOGCONFIG(TAG, "Running setup for '%s'", this->get_name().c_str());
static bool initialized = false;
if (!initialized) {
adc_init();

View File

@@ -115,7 +115,7 @@ void AHT10Component::read_data_() {
if (this->humidity_sensor_ == nullptr) {
ESP_LOGV(TAG, "Invalid humidity (reading not required)");
} else {
ESP_LOGD(TAG, "Invalid humidity, retrying...");
ESP_LOGD(TAG, "Invalid humidity, retrying");
if (this->write(AHT10_MEASURE_CMD, sizeof(AHT10_MEASURE_CMD)) != i2c::ERROR_OK) {
this->status_set_warning(ESP_LOG_MSG_COMM_FAIL);
}

View File

@@ -282,7 +282,7 @@ void AS3935Component::display_oscillator(bool state, uint8_t osc) {
// based on the resonance frequency of the antenna and so it should be trimmed
// before the calibration is done.
bool AS3935Component::calibrate_oscillator() {
ESP_LOGI(TAG, "Starting oscillators calibration...");
ESP_LOGI(TAG, "Starting oscillators calibration");
this->write_register(CALIB_RCO, WIPE_ALL, DIRECT_COMMAND, 0); // Send command to calibrate the oscillators
this->display_oscillator(true, 2);
@@ -307,7 +307,7 @@ bool AS3935Component::calibrate_oscillator() {
}
void AS3935Component::tune_antenna() {
ESP_LOGI(TAG, "Starting antenna tuning...");
ESP_LOGI(TAG, "Starting antenna tuning");
uint8_t div_ratio = this->read_div_ratio();
uint8_t tune_val = this->read_capacitance();
ESP_LOGI(TAG, "Division Ratio is set to: %d", div_ratio);

View File

@@ -75,7 +75,7 @@ void AT581XComponent::setup() { ESP_LOGCONFIG(TAG, "Running setup"); }
void AT581XComponent::dump_config() { LOG_I2C_DEVICE(this); }
#define ARRAY_SIZE(X) (sizeof(X) / sizeof((X)[0]))
bool AT581XComponent::i2c_write_config() {
ESP_LOGCONFIG(TAG, "Writing new config for AT581X...");
ESP_LOGCONFIG(TAG, "Writing new config for AT581X");
ESP_LOGCONFIG(TAG, "Frequency: %dMHz", this->freq_);
ESP_LOGCONFIG(TAG, "Sensing distance: %d", this->delta_);
ESP_LOGCONFIG(TAG, "Power: %dµA", this->power_);

View File

@@ -686,7 +686,7 @@ void ATM90E32Component::restore_power_offset_calibrations_() {
}
void ATM90E32Component::clear_gain_calibrations() {
ESP_LOGI(TAG, "[CALIBRATION] Clearing stored gain calibrations and restoring config-defined values...");
ESP_LOGI(TAG, "[CALIBRATION] Clearing stored gain calibrations and restoring config-defined values");
for (int phase = 0; phase < 3; phase++) {
gain_phase_[phase].voltage_gain = this->phase_[phase].voltage_gain_;

View File

@@ -527,7 +527,7 @@ void BedJetHub::dispatch_status_() {
}
if (this->timeout_ > 0 && diff > this->timeout_ && this->parent()->enabled) {
ESP_LOGW(TAG, "[%s] Timed out after %" PRId32 " sec. Retrying...", this->get_name().c_str(), this->timeout_);
ESP_LOGW(TAG, "[%s] Timed out after %" PRId32 " sec. Retrying", this->get_name().c_str(), this->timeout_);
// set_enabled(false) will only close the connection if state != IDLE.
this->parent()->set_state(espbt::ClientState::CONNECTING);
this->parent()->set_enabled(false);

View File

@@ -256,7 +256,7 @@ void BekenSPILEDStripLightOutput::write_state(light::LightState *state) {
this->last_refresh_ = now;
this->mark_shown_();
ESP_LOGVV(TAG, "Writing RGB values to bus...");
ESP_LOGVV(TAG, "Writing RGB values to bus");
if (spi_data == nullptr) {
ESP_LOGE(TAG, "SPI not initialized");

View File

@@ -68,8 +68,7 @@ void binary_sensor::MultiClickTrigger::on_state_(bool state) {
*this->at_index_ = *this->at_index_ + 1;
}
void binary_sensor::MultiClickTrigger::schedule_cooldown_() {
ESP_LOGV(TAG, "Multi Click: Invalid length of press, starting cooldown of %" PRIu32 " ms...",
this->invalid_cooldown_);
ESP_LOGV(TAG, "Multi Click: Invalid length of press, starting cooldown of %" PRIu32 " ms", this->invalid_cooldown_);
this->is_in_cooldown_ = true;
this->set_timeout("cooldown", this->invalid_cooldown_, [this]() {
ESP_LOGV(TAG, "Multi Click: Cooldown ended, matching is now enabled again.");

View File

@@ -100,7 +100,7 @@ void BL0906::handle_actions_() {
for (int i = 0; i < this->action_queue_.size(); i++) {
ptr_func = this->action_queue_[i];
if (ptr_func) {
ESP_LOGI(TAG, "HandleActionCallback[%d]...", i);
ESP_LOGI(TAG, "HandleActionCallback[%d]", i);
(this->*ptr_func)();
}
}

View File

@@ -207,7 +207,7 @@ inline uint8_t oversampling_to_time(BME280Oversampling over_sampling) { return (
void BME280Component::update() {
// Enable sensor
ESP_LOGV(TAG, "Sending conversion request...");
ESP_LOGV(TAG, "Sending conversion request");
uint8_t meas_value = 0;
meas_value |= (this->temperature_oversampling_ & 0b111) << 5;
meas_value |= (this->pressure_oversampling_ & 0b111) << 2;

View File

@@ -126,37 +126,37 @@ void BMI160Component::internal_setup_(int stage) {
return;
}
ESP_LOGV(TAG, " Bringing accelerometer out of sleep...");
ESP_LOGV(TAG, " Bringing accelerometer out of sleep");
if (!this->write_byte(BMI160_REGISTER_CMD, (uint8_t) Cmd::ACCL_SET_PMU_MODE | (uint8_t) AcclPmuMode::NORMAL)) {
this->mark_failed();
return;
}
ESP_LOGV(TAG, " Waiting for accelerometer to wake up...");
ESP_LOGV(TAG, " Waiting for accelerometer to wake up");
// need to wait (max delay in datasheet) because we can't send commands while another is in progress
// min 5ms, 10ms
this->set_timeout(10, [this]() { this->internal_setup_(1); });
break;
case 1:
ESP_LOGV(TAG, " Bringing gyroscope out of sleep...");
ESP_LOGV(TAG, " Bringing gyroscope out of sleep");
if (!this->write_byte(BMI160_REGISTER_CMD, (uint8_t) Cmd::GYRO_SET_PMU_MODE | (uint8_t) GyroPmuMode::NORMAL)) {
this->mark_failed();
return;
}
ESP_LOGV(TAG, " Waiting for gyroscope to wake up...");
ESP_LOGV(TAG, " Waiting for gyroscope to wake up");
// wait between 51 & 81ms, doing 100 to be safe
this->set_timeout(10, [this]() { this->internal_setup_(2); });
break;
case 2:
ESP_LOGV(TAG, " Setting up Gyro Config...");
ESP_LOGV(TAG, " Setting up Gyro Config");
uint8_t gyro_config = (uint8_t) GyroBandwidth::OSR4 | (uint8_t) GyroOuputDataRate::HZ_25;
ESP_LOGV(TAG, " Output gyro_config: 0b" BYTE_TO_BINARY_PATTERN, BYTE_TO_BINARY(gyro_config));
if (!this->write_byte(BMI160_REGISTER_GYRO_CONFIG, gyro_config)) {
this->mark_failed();
return;
}
ESP_LOGV(TAG, " Setting up Gyro Range...");
ESP_LOGV(TAG, " Setting up Gyro Range");
uint8_t gyro_range = (uint8_t) GyroRange::RANGE_2000_DPS;
ESP_LOGV(TAG, " Output gyro_range: 0b" BYTE_TO_BINARY_PATTERN, BYTE_TO_BINARY(gyro_range));
if (!this->write_byte(BMI160_REGISTER_GYRO_RANGE, gyro_range)) {
@@ -164,7 +164,7 @@ void BMI160Component::internal_setup_(int stage) {
return;
}
ESP_LOGV(TAG, " Setting up Accel Config...");
ESP_LOGV(TAG, " Setting up Accel Config");
uint8_t accel_config =
(uint8_t) AcclFilterMode::PERF | (uint8_t) AcclBandwidth::RES_AVG16 | (uint8_t) AccelOutputDataRate::HZ_25;
ESP_LOGV(TAG, " Output accel_config: 0b" BYTE_TO_BINARY_PATTERN, BYTE_TO_BINARY(accel_config));
@@ -172,7 +172,7 @@ void BMI160Component::internal_setup_(int stage) {
this->mark_failed();
return;
}
ESP_LOGV(TAG, " Setting up Accel Range...");
ESP_LOGV(TAG, " Setting up Accel Range");
uint8_t accel_range = (uint8_t) AccelRange::RANGE_16G;
ESP_LOGV(TAG, " Output accel_range: 0b" BYTE_TO_BINARY_PATTERN, BYTE_TO_BINARY(accel_range));
if (!this->write_byte(BMI160_REGISTER_ACCEL_RANGE, accel_range)) {
@@ -219,7 +219,7 @@ void BMI160Component::update() {
return;
}
ESP_LOGV(TAG, " Updating BMI160...");
ESP_LOGV(TAG, " Updating BMI160");
int16_t data[6];
if (this->read_le_int16_(BMI160_REGISTER_DATA_GYRO_X_LSB, data, 6) != i2c::ERROR_OK) {
this->status_set_warning();

View File

@@ -129,7 +129,7 @@ void BMP085Component::read_pressure_() {
this->status_clear_warning();
}
bool BMP085Component::set_mode_(uint8_t mode) {
ESP_LOGV(TAG, "Setting mode to 0x%02X...", mode);
ESP_LOGV(TAG, "Setting mode to 0x%02X", mode);
return this->write_byte(BMP085_REGISTER_CONTROL, mode);
}
float BMP085Component::get_setup_priority() const { return setup_priority::DATA; }

View File

@@ -155,7 +155,7 @@ inline uint8_t oversampling_to_time(BMP280Oversampling over_sampling) { return (
void BMP280Component::update() {
// Enable sensor
ESP_LOGV(TAG, "Sending conversion request...");
ESP_LOGV(TAG, "Sending conversion request");
uint8_t meas_value = 0;
meas_value |= (this->temperature_oversampling_ & 0b111) << 5;
meas_value |= (this->pressure_oversampling_ & 0b111) << 2;

View File

@@ -38,7 +38,7 @@ void CM1106Component::update() {
}
if (response[0] != 0x16 || response[1] != 0x05 || response[2] != 0x01) {
ESP_LOGW(TAG, "Got wrong UART response from CM1106: %02X %02X %02X %02X...", response[0], response[1], response[2],
ESP_LOGW(TAG, "Got wrong UART response from CM1106: %02X %02X %02X %02X", response[0], response[1], response[2],
response[3]);
this->status_set_warning();
return;

View File

@@ -22,7 +22,7 @@ static const uint8_t DAC7678_REG_INTERNAL_REF_1 = 0x90;
void DAC7678Output::setup() {
ESP_LOGCONFIG(TAG, "Running setup");
ESP_LOGV(TAG, "Resetting device...");
ESP_LOGV(TAG, "Resetting device");
// Reset device
if (!this->write_byte_16(DAC7678_REG_SOFTWARE_RESET, 0x0000)) {

View File

@@ -21,7 +21,7 @@ uint8_t Command::execute(DfrobotSen0395Component *parent) {
if (this->retries_left_ > 0) {
this->retries_left_ -= 1;
this->cmd_sent_ = false;
ESP_LOGD(TAG, "Retrying...");
ESP_LOGD(TAG, "Retrying");
return 0;
} else {
this->parent_->find_prompt_();
@@ -33,7 +33,7 @@ uint8_t Command::execute(DfrobotSen0395Component *parent) {
if (this->retries_left_ > 0) {
this->retries_left_ -= 1;
this->cmd_sent_ = false;
ESP_LOGD(TAG, "Retrying...");
ESP_LOGD(TAG, "Retrying");
return 0;
} else {
this->parent_->find_prompt_();
@@ -51,7 +51,7 @@ uint8_t Command::execute(DfrobotSen0395Component *parent) {
if (this->retries_left_ > 0) {
this->retries_left_ -= 1;
this->cmd_sent_ = false;
ESP_LOGD(TAG, "Retrying...");
ESP_LOGD(TAG, "Retrying");
} else {
return 1; // Command done
}

View File

@@ -84,7 +84,7 @@ class ESP32Preferences : public ESPPreferences {
if (err == 0)
return;
ESP_LOGW(TAG, "nvs_open failed: %s - erasing NVS...", esp_err_to_name(err));
ESP_LOGW(TAG, "nvs_open failed: %s - erasing NVS", esp_err_to_name(err));
nvs_flash_deinit();
nvs_flash_erase();
nvs_flash_init();

View File

@@ -270,14 +270,14 @@ void ESP32BLE::loop() {
case BLE_COMPONENT_STATE_DISABLED:
return;
case BLE_COMPONENT_STATE_DISABLE: {
ESP_LOGD(TAG, "Disabling BLE...");
ESP_LOGD(TAG, "Disabling");
for (auto *ble_event_handler : this->ble_status_event_handlers_) {
ble_event_handler->ble_before_disabled_event_handler();
}
if (!ble_dismantle_()) {
ESP_LOGE(TAG, "BLE could not be dismantled");
ESP_LOGE(TAG, "Could not be dismantled");
this->mark_failed();
return;
}
@@ -285,11 +285,11 @@ void ESP32BLE::loop() {
return;
}
case BLE_COMPONENT_STATE_ENABLE: {
ESP_LOGD(TAG, "Enabling BLE...");
ESP_LOGD(TAG, "Enabling");
this->state_ = BLE_COMPONENT_STATE_OFF;
if (!ble_setup_()) {
ESP_LOGE(TAG, "BLE could not be set up");
ESP_LOGE(TAG, "Could not be set up");
this->mark_failed();
return;
}

View File

@@ -172,7 +172,7 @@ void ESP32BLETracker::loop() {
(this->scan_set_param_failed_ && this->scanner_state_ == ScannerState::RUNNING)) {
this->stop_scan_();
if (this->scan_start_fail_count_ == std::numeric_limits<uint8_t>::max()) {
ESP_LOGE(TAG, "ESP-IDF BLE scan could not restart after %d attempts, rebooting to restore BLE stack...",
ESP_LOGE(TAG, "Scan could not restart after %d attempts, rebooting to restore stack (IDF)",
std::numeric_limits<uint8_t>::max());
App.reboot();
}
@@ -219,10 +219,10 @@ void ESP32BLETracker::loop() {
for (auto *client : this->clients_) {
if (client->state() == ClientState::DISCOVERED) {
if (this->scanner_state_ == ScannerState::RUNNING) {
ESP_LOGD(TAG, "Stopping scan to make connection...");
ESP_LOGD(TAG, "Stopping scan to make connection");
this->stop_scan_();
} else if (this->scanner_state_ == ScannerState::IDLE) {
ESP_LOGD(TAG, "Promoting client to connect...");
ESP_LOGD(TAG, "Promoting client to connect");
// We only want to promote one client at a time.
// once the scanner is fully stopped.
#ifdef USE_ESP32_BLE_SOFTWARE_COEXISTENCE
@@ -306,7 +306,7 @@ void ESP32BLETracker::start_scan_(bool first) {
// Start timeout before scan is started. Otherwise scan never starts if any error.
this->set_timeout("scan", this->scan_duration_ * 2000, []() {
ESP_LOGE(TAG, "ESP-IDF BLE scan never terminated, rebooting to restore BLE stack...");
ESP_LOGE(TAG, "Scan never terminated, rebooting to restore stack (IDF)");
App.reboot();
});

View File

@@ -324,10 +324,10 @@ void ESP32ImprovComponent::process_incoming_data_() {
this->incoming_data_.clear();
}
} else if (this->incoming_data_.size() - 2 > length) {
ESP_LOGV(TAG, "Too much data received or data malformed; resetting buffer...");
ESP_LOGV(TAG, "Too much data received or data malformed; resetting buffer");
this->incoming_data_.clear();
} else {
ESP_LOGV(TAG, "Waiting for split data packets...");
ESP_LOGV(TAG, "Waiting for split data packets");
}
}

View File

@@ -143,7 +143,7 @@ void ESP32RMTLEDStripLightOutput::write_state(light::LightState *state) {
this->last_refresh_ = now;
this->mark_shown_();
ESP_LOGVV(TAG, "Writing RGB values to bus...");
ESP_LOGVV(TAG, "Writing RGB values to bus");
#if ESP_IDF_VERSION_MAJOR >= 5
esp_err_t error = rmt_tx_wait_all_done(this->channel_, 1000);

View File

@@ -169,7 +169,7 @@ class ESP8266Preferences : public ESPPreferences {
void setup() {
s_flash_storage = new uint32_t[ESP8266_FLASH_STORAGE_SIZE]; // NOLINT
ESP_LOGVV(TAG, "Loading preferences from flash...");
ESP_LOGVV(TAG, "Loading preferences from flash");
{
InterruptLock lock;

View File

@@ -119,7 +119,7 @@ void ESPHomeOTAComponent::handle_() {
return;
}
ESP_LOGD(TAG, "Starting update from %s...", this->client_->getpeername().c_str());
ESP_LOGD(TAG, "Starting update from %s", this->client_->getpeername().c_str());
this->status_set_warning();
#ifdef USE_OTA_STATE_CALLBACK
this->state_callback_.call(ota::OTA_STARTED, 0.0f, 0);

View File

@@ -10,7 +10,7 @@ static const char *const TAG = "factory_reset.button";
void FactoryResetButton::dump_config() { LOG_BUTTON("", "Factory Reset Button", this); }
void FactoryResetButton::press_action() {
ESP_LOGI(TAG, "Resetting...");
ESP_LOGI(TAG, "Resetting");
// Let MQTT settle a bit
delay(100); // NOLINT
global_preferences->reset();

View File

@@ -14,7 +14,7 @@ void FactoryResetSwitch::write_state(bool state) {
this->publish_state(false);
if (state) {
ESP_LOGI(TAG, "Resetting...");
ESP_LOGI(TAG, "Resetting");
// Let MQTT settle a bit
delay(100); // NOLINT
global_preferences->reset();

View File

@@ -33,7 +33,7 @@ void FastLEDLightOutput::write_state(light::LightState *state) {
this->last_refresh_ = now;
this->mark_shown_();
ESP_LOGVV(TAG, "Writing RGB values to bus...");
ESP_LOGVV(TAG, "Writing RGB values to bus");
this->controller_->showLeds(this->state_parent_->current_values.get_brightness() * 255);
}

View File

@@ -242,7 +242,7 @@ haier_protocol::HandlerError HaierClimateBase::timeout_default_handler_(haier_pr
}
void HaierClimateBase::setup() {
ESP_LOGI(TAG, "Haier initialization...");
ESP_LOGCONFIG(TAG, "Running setup");
// Set timestamp here to give AC time to boot
this->last_request_timestamp_ = std::chrono::steady_clock::now();
this->set_phase(ProtocolPhases::SENDING_INIT_1);
@@ -286,7 +286,7 @@ void HaierClimateBase::loop() {
if (this->action_request_.has_value() && this->prepare_pending_action()) {
this->set_phase(ProtocolPhases::SENDING_ACTION_COMMAND);
} else if (this->next_hvac_settings_.valid || this->force_send_control_) {
ESP_LOGV(TAG, "Control packet is pending...");
ESP_LOGV(TAG, "Control packet is pending");
this->set_phase(ProtocolPhases::SENDING_CONTROL);
if (this->next_hvac_settings_.valid) {
this->current_hvac_settings_ = this->next_hvac_settings_;

View File

@@ -48,7 +48,7 @@ void OtaHttpRequestComponent::flash() {
return;
}
ESP_LOGI(TAG, "Starting update...");
ESP_LOGI(TAG, "Starting update");
#ifdef USE_OTA_STATE_CALLBACK
this->state_callback_.call(ota::OTA_STARTED, 0.0f, 0);
#endif

View File

@@ -40,7 +40,7 @@ void ArduinoI2CBus::setup() {
this->initialized_ = true;
if (this->scan_) {
ESP_LOGV(TAG, "Scanning i2c bus for active devices...");
ESP_LOGV(TAG, "Scanning bus for active devices");
this->i2c_scan_();
}
}

View File

@@ -75,7 +75,7 @@ void IDFI2CBus::setup() {
}
initialized_ = true;
if (this->scan_) {
ESP_LOGV(TAG, "Scanning i2c bus for active devices...");
ESP_LOGV(TAG, "Scanning bus for active devices");
this->i2c_scan_();
}
}

View File

@@ -158,7 +158,7 @@ void LD2420Component::apply_config_action() {
ESP_LOGCONFIG(TAG, "No configuration change detected");
return;
}
ESP_LOGCONFIG(TAG, "Reconfiguring LD2420...");
ESP_LOGCONFIG(TAG, "Reconfiguring LD2420");
if (this->set_config_mode(true) == LD2420_ERROR_TIMEOUT) {
ESP_LOGE(TAG, "LD2420 module has failed to respond, check baud rate and serial connections.");
this->mark_failed();
@@ -180,7 +180,7 @@ void LD2420Component::apply_config_action() {
}
void LD2420Component::factory_reset_action() {
ESP_LOGCONFIG(TAG, "Setting factory defaults...");
ESP_LOGCONFIG(TAG, "Setting factory defaults");
if (this->set_config_mode(true) == LD2420_ERROR_TIMEOUT) {
ESP_LOGE(TAG, "LD2420 module has failed to respond, check baud rate and serial connections.");
this->mark_failed();
@@ -209,7 +209,7 @@ void LD2420Component::factory_reset_action() {
}
void LD2420Component::restart_module_action() {
ESP_LOGCONFIG(TAG, "Restarting LD2420 module...");
ESP_LOGCONFIG(TAG, "Restarting LD2420 module");
this->send_module_restart();
this->set_timeout(250, [this]() {
this->set_config_mode(true);

View File

@@ -139,7 +139,7 @@ void LEDCOutput::write_state(float state) {
}
void LEDCOutput::setup() {
ESP_LOGV(TAG, "Entering setup...");
ESP_LOGCONFIG(TAG, "Running setup");
#ifdef USE_ARDUINO
this->update_frequency(this->frequency_);
this->turn_off();
@@ -207,14 +207,14 @@ void LEDCOutput::update_frequency(float frequency) {
this->bit_depth_ = bit_depth_opt.value_or(8);
this->frequency_ = frequency;
#ifdef USE_ARDUINO
ESP_LOGV(TAG, "Using Arduino API - Trying to define channel, frequency and bit depth...");
ESP_LOGV(TAG, "Using Arduino API - Trying to define channel, frequency and bit depth");
u_int32_t configured_frequency = 0;
// Configure LEDC channel, frequency and bit depth with fallback
int attempt_count_max = SETUP_ATTEMPT_COUNT_MAX;
while (attempt_count_max > 0 && configured_frequency == 0) {
ESP_LOGV(TAG, "Initializing channel %u with frequency %.1f and bit depth of %u...", this->channel_,
this->frequency_, this->bit_depth_);
ESP_LOGV(TAG, "Initializing channel %u with frequency %.1f and bit depth of %u", this->channel_, this->frequency_,
this->bit_depth_);
configured_frequency = ledcSetup(this->channel_, frequency, this->bit_depth_);
if (configured_frequency != 0) {
this->initialized_ = true;

View File

@@ -306,7 +306,7 @@ void LTRAlsPs501Component::configure_als_() {
uint8_t tries = MAX_TRIES;
do {
ESP_LOGV(TAG, "Waiting for ALS device to become active...");
ESP_LOGV(TAG, "Waiting for ALS device to become active");
delay(2);
als_ctrl.raw = this->reg((uint8_t) CommandRegisters::ALS_CONTR).get();
} while (!als_ctrl.als_mode_active && tries--); // while active mode is not set - keep waiting

View File

@@ -298,7 +298,7 @@ void LTRAlsPsComponent::configure_als_() {
uint8_t tries = MAX_TRIES;
do {
ESP_LOGV(TAG, "Waiting for device to become active...");
ESP_LOGV(TAG, "Waiting for device to become active");
delay(2);
als_ctrl.raw = this->reg((uint8_t) CommandRegisters::ALS_CONTR).get();
} while (!als_ctrl.active_mode && tries--); // while active mode is not set - keep waiting

View File

@@ -13,14 +13,14 @@ void M5Stack8AngleComponent::setup() {
err = this->read(nullptr, 0);
if (err != i2c::NO_ERROR) {
ESP_LOGE(TAG, "I2C error %02X...", err);
ESP_LOGE(TAG, "I2C error %02X", err);
this->mark_failed();
return;
};
err = this->read_register(M5STACK_8ANGLE_REGISTER_FW_VERSION, &this->fw_version_, 1);
if (err != i2c::NO_ERROR) {
ESP_LOGE(TAG, "I2C error %02X...", err);
ESP_LOGE(TAG, "I2C error %02X", err);
this->mark_failed();
return;
};

View File

@@ -95,28 +95,28 @@ bool MAX31856Sensor::has_fault_() {
this->status_set_warning();
if ((faults & MAX31856_FAULT_CJRANGE) == MAX31856_FAULT_CJRANGE) {
ESP_LOGW(TAG, "Cold Junction Out-of-Range: '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Cold Junction Out-of-Range: '%s'", this->name_.c_str());
}
if ((faults & MAX31856_FAULT_TCRANGE) == MAX31856_FAULT_TCRANGE) {
ESP_LOGW(TAG, "Thermocouple Out-of-Range: '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Thermocouple Out-of-Range: '%s'", this->name_.c_str());
}
if ((faults & MAX31856_FAULT_CJHIGH) == MAX31856_FAULT_CJHIGH) {
ESP_LOGW(TAG, "Cold-Junction High Fault: '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Cold-Junction High Fault: '%s'", this->name_.c_str());
}
if ((faults & MAX31856_FAULT_CJLOW) == MAX31856_FAULT_CJLOW) {
ESP_LOGW(TAG, "Cold-Junction Low Fault: '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Cold-Junction Low Fault: '%s'", this->name_.c_str());
}
if ((faults & MAX31856_FAULT_TCHIGH) == MAX31856_FAULT_TCHIGH) {
ESP_LOGW(TAG, "Thermocouple Temperature High Fault: '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Thermocouple Temperature High Fault: '%s'", this->name_.c_str());
}
if ((faults & MAX31856_FAULT_TCLOW) == MAX31856_FAULT_TCLOW) {
ESP_LOGW(TAG, "Thermocouple Temperature Low Fault: '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Thermocouple Temperature Low Fault: '%s'", this->name_.c_str());
}
if ((faults & MAX31856_FAULT_OVUV) == MAX31856_FAULT_OVUV) {
ESP_LOGW(TAG, "Overvoltage or Undervoltage Input Fault: '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Overvoltage or Undervoltage Input Fault: '%s'", this->name_.c_str());
}
if ((faults & MAX31856_FAULT_OPEN) == MAX31856_FAULT_OPEN) {
ESP_LOGW(TAG, "Thermocouple Open-Circuit Fault (possibly not connected): '%s'...", this->name_.c_str());
ESP_LOGW(TAG, "Thermocouple Open-Circuit Fault (possibly not connected): '%s'", this->name_.c_str());
}
return true;

View File

@@ -16,7 +16,7 @@ void MICS4514Component::setup() {
uint8_t power_mode;
this->read_register(POWER_MODE_REGISTER, &power_mode, 1);
if (power_mode == 0x00) {
ESP_LOGCONFIG(TAG, "Waking up MICS 4514, sensors will have data after 3 minutes...");
ESP_LOGCONFIG(TAG, "Waking up MICS 4514, sensors will have data after 3 minutes");
power_mode = 0x01;
this->write_register(POWER_MODE_REGISTER, &power_mode, 1);
delay(100); // NOLINT

View File

@@ -29,7 +29,7 @@ void MPU6050Component::setup() {
return;
}
ESP_LOGV(TAG, " Setting up Power Management...");
ESP_LOGV(TAG, " Setting up Power Management");
// Setup power management
uint8_t power_management;
if (!this->read_byte(MPU6050_REGISTER_POWER_MANAGEMENT_1, &power_management)) {
@@ -50,7 +50,7 @@ void MPU6050Component::setup() {
return;
}
ESP_LOGV(TAG, " Setting up Gyro Config...");
ESP_LOGV(TAG, " Setting up Gyro Config");
// Set scale - 2000DPS
uint8_t gyro_config;
if (!this->read_byte(MPU6050_REGISTER_GYRO_CONFIG, &gyro_config)) {
@@ -66,7 +66,7 @@ void MPU6050Component::setup() {
return;
}
ESP_LOGV(TAG, " Setting up Accel Config...");
ESP_LOGV(TAG, " Setting up Accel Config");
// Set range - 2G
uint8_t accel_config;
if (!this->read_byte(MPU6050_REGISTER_ACCEL_CONFIG, &accel_config)) {
@@ -99,7 +99,7 @@ void MPU6050Component::dump_config() {
}
void MPU6050Component::update() {
ESP_LOGV(TAG, " Updating MPU6050...");
ESP_LOGV(TAG, "Updating");
uint16_t raw_data[7];
if (!this->read_bytes_16(MPU6050_REGISTER_ACCEL_XOUT_H, raw_data, 7)) {
this->status_set_warning();

View File

@@ -33,7 +33,7 @@ void MPU6886Component::setup() {
return;
}
ESP_LOGV(TAG, " Setting up Power Management...");
ESP_LOGV(TAG, " Setting up Power Management");
// Setup power management
uint8_t power_management;
if (!this->read_byte(MPU6886_REGISTER_POWER_MANAGEMENT_1, &power_management)) {
@@ -54,7 +54,7 @@ void MPU6886Component::setup() {
return;
}
ESP_LOGV(TAG, " Setting up Gyroscope Config...");
ESP_LOGV(TAG, " Setting up Gyroscope Config");
// Set scale - 2000DPS
uint8_t gyro_config;
if (!this->read_byte(MPU6886_REGISTER_GYRO_CONFIG, &gyro_config)) {
@@ -70,7 +70,7 @@ void MPU6886Component::setup() {
return;
}
ESP_LOGV(TAG, " Setting up Accelerometer Config...");
ESP_LOGV(TAG, " Setting up Accelerometer Config");
// Set range - 2G
uint8_t accel_config;
if (!this->read_byte(MPU6886_REGISTER_ACCEL_CONFIG, &accel_config)) {
@@ -104,7 +104,7 @@ void MPU6886Component::dump_config() {
}
void MPU6886Component::update() {
ESP_LOGV(TAG, " Updating MPU6886...");
ESP_LOGV(TAG, " Updating");
uint16_t raw_data[7];
if (!this->read_bytes_16(MPU6886_REGISTER_ACCEL_XOUT_H, raw_data, 7)) {
this->status_set_warning();

View File

@@ -248,10 +248,10 @@ void MSA3xxComponent::loop() {
}
void MSA3xxComponent::update() {
ESP_LOGV(TAG, "Updating MSA3xx...");
ESP_LOGV(TAG, "Updating");
if (!this->is_ready()) {
ESP_LOGV(TAG, "Component MSA3xx not ready for update");
ESP_LOGV(TAG, "Not ready for update");
return;
}
ESP_LOGV(TAG, "Acceleration: {x = %+1.3f m/s², y = %+1.3f m/s², z = %+1.3f m/s²}; ", this->data_.x, this->data_.y,

View File

@@ -249,7 +249,7 @@ bool Nextion::upload_tft(uint32_t baud_rate, bool exit_reparse) {
ESP_LOGV(TAG, "Connection closed");
return this->upload_end_(false);
} else {
ESP_LOGV(TAG, "File size check passed. Proceeding...");
ESP_LOGV(TAG, "File size check passed. Proceeding");
}
this->content_length_ = this->tft_size_;

View File

@@ -241,7 +241,7 @@ bool Nextion::upload_tft(uint32_t baud_rate, bool exit_reparse) {
ESP_LOGV(TAG, "Connection closed");
return this->upload_end_(false);
} else {
ESP_LOGV(TAG, "File size check passed. Proceeding...");
ESP_LOGV(TAG, "File size check passed. Proceeding");
}
this->content_length_ = this->tft_size_;

View File

@@ -56,7 +56,7 @@ void OnlineImage::draw(int x, int y, display::Display *display, Color color_on,
void OnlineImage::release() {
if (this->buffer_) {
ESP_LOGV(TAG, "Deallocating old buffer...");
ESP_LOGV(TAG, "Deallocating old buffer");
this->allocator_.deallocate(this->buffer_, this->get_buffer_size_());
this->data_start_ = nullptr;
this->buffer_ = nullptr;

View File

@@ -28,7 +28,7 @@ static const uint8_t PCA9685_MODE1_SLEEP = 0b00010000;
void PCA9685Output::setup() {
ESP_LOGCONFIG(TAG, "Running setup");
ESP_LOGV(TAG, " Resetting devices...");
ESP_LOGV(TAG, " Resetting devices");
if (!this->write_bytes(PCA9685_REGISTER_SOFTWARE_RESET, nullptr, 0)) {
this->mark_failed();
return;

View File

@@ -19,7 +19,7 @@ void PN532::setup() {
// Get version data
if (!this->write_command_({PN532_COMMAND_VERSION_DATA})) {
ESP_LOGW(TAG, "Error sending version command, trying again...");
ESP_LOGW(TAG, "Error sending version command, trying again");
if (!this->write_command_({PN532_COMMAND_VERSION_DATA})) {
ESP_LOGE(TAG, "Error sending version command");
this->mark_failed();
@@ -208,21 +208,21 @@ void PN532::loop() {
}
}
} else if (next_task_ == CLEAN) {
ESP_LOGD(TAG, " Tag cleaning...");
ESP_LOGD(TAG, " Tag cleaning");
if (!this->clean_tag_(nfcid)) {
ESP_LOGE(TAG, " Tag was not fully cleaned successfully");
}
ESP_LOGD(TAG, " Tag cleaned!");
} else if (next_task_ == FORMAT) {
ESP_LOGD(TAG, " Tag formatting...");
ESP_LOGD(TAG, " Tag formatting");
if (!this->format_tag_(nfcid)) {
ESP_LOGE(TAG, "Error formatting tag as NDEF");
}
ESP_LOGD(TAG, " Tag formatted!");
} else if (next_task_ == WRITE) {
if (this->next_task_message_to_write_ != nullptr) {
ESP_LOGD(TAG, " Tag writing...");
ESP_LOGD(TAG, " Tag formatting...");
ESP_LOGD(TAG, " Tag writing");
ESP_LOGD(TAG, " Tag formatting");
if (!this->format_tag_(nfcid)) {
ESP_LOGE(TAG, " Tag could not be formatted for writing");
} else {
@@ -281,7 +281,7 @@ bool PN532::write_command_(const std::vector<uint8_t> &data) {
}
bool PN532::read_ack_() {
ESP_LOGV(TAG, "Reading ACK...");
ESP_LOGV(TAG, "Reading ACK");
std::vector<uint8_t> data;
if (!this->read_data(data, 6)) {

View File

@@ -51,7 +51,7 @@ bool PN532Spi::read_data(std::vector<uint8_t> &data, uint8_t len) {
delay(2);
this->write_byte(0x03);
ESP_LOGV(TAG, "Reading data...");
ESP_LOGV(TAG, "Reading data");
data.resize(len);
this->read_array(data.data(), len);

View File

@@ -830,7 +830,7 @@ void PN7150::process_rf_intf_activated_oid_(nfc::NciMessage &rx) { // an endpoi
switch (this->next_task_) {
case EP_CLEAN:
ESP_LOGD(TAG, " Tag cleaning...");
ESP_LOGD(TAG, " Tag cleaning");
if (this->clean_endpoint_(working_endpoint.tag->get_uid()) != nfc::STATUS_OK) {
ESP_LOGE(TAG, " Tag cleaning incomplete");
}
@@ -838,7 +838,7 @@ void PN7150::process_rf_intf_activated_oid_(nfc::NciMessage &rx) { // an endpoi
break;
case EP_FORMAT:
ESP_LOGD(TAG, " Tag formatting...");
ESP_LOGD(TAG, " Tag formatting");
if (this->format_endpoint_(working_endpoint.tag->get_uid()) != nfc::STATUS_OK) {
ESP_LOGE(TAG, "Error formatting tag as NDEF");
}
@@ -847,8 +847,8 @@ void PN7150::process_rf_intf_activated_oid_(nfc::NciMessage &rx) { // an endpoi
case EP_WRITE:
if (this->next_task_message_to_write_ != nullptr) {
ESP_LOGD(TAG, " Tag writing...");
ESP_LOGD(TAG, " Tag formatting...");
ESP_LOGD(TAG, " Tag writing");
ESP_LOGD(TAG, " Tag formatting");
if (this->format_endpoint_(working_endpoint.tag->get_uid()) != nfc::STATUS_OK) {
ESP_LOGE(TAG, " Tag could not be formatted for writing");
} else {

View File

@@ -854,7 +854,7 @@ void PN7160::process_rf_intf_activated_oid_(nfc::NciMessage &rx) { // an endpoi
switch (this->next_task_) {
case EP_CLEAN:
ESP_LOGD(TAG, " Tag cleaning...");
ESP_LOGD(TAG, " Tag cleaning");
if (this->clean_endpoint_(working_endpoint.tag->get_uid()) != nfc::STATUS_OK) {
ESP_LOGE(TAG, " Tag cleaning incomplete");
}
@@ -862,7 +862,7 @@ void PN7160::process_rf_intf_activated_oid_(nfc::NciMessage &rx) { // an endpoi
break;
case EP_FORMAT:
ESP_LOGD(TAG, " Tag formatting...");
ESP_LOGD(TAG, " Tag formatting");
if (this->format_endpoint_(working_endpoint.tag->get_uid()) != nfc::STATUS_OK) {
ESP_LOGE(TAG, "Error formatting tag as NDEF");
}
@@ -871,8 +871,8 @@ void PN7160::process_rf_intf_activated_oid_(nfc::NciMessage &rx) { // an endpoi
case EP_WRITE:
if (this->next_task_message_to_write_ != nullptr) {
ESP_LOGD(TAG, " Tag writing...");
ESP_LOGD(TAG, " Tag formatting...");
ESP_LOGD(TAG, " Tag writing");
ESP_LOGD(TAG, " Tag formatting");
if (this->format_endpoint_(working_endpoint.tag->get_uid()) != nfc::STATUS_OK) {
ESP_LOGE(TAG, " Tag could not be formatted for writing");
} else {

View File

@@ -24,7 +24,7 @@ void QrCode::set_ecc(qrcodegen_Ecc ecc) {
}
void QrCode::generate_qr_code() {
ESP_LOGV(TAG, "Generating QR code...");
ESP_LOGV(TAG, "Generating QR code");
uint8_t tempbuffer[qrcodegen_BUFFER_LEN_MAX];
if (!qrcodegen_encodeText(this->value_.c_str(), tempbuffer, this->qr_, this->ecc_, qrcodegen_VERSION_MIN,

View File

@@ -46,7 +46,7 @@ void RC522::setup() {
reset_pin_->pin_mode(gpio::FLAG_INPUT);
if (!reset_pin_->digital_read()) { // The MFRC522 chip is in power down mode.
ESP_LOGV(TAG, "Power down mode detected. Hard resetting...");
ESP_LOGV(TAG, "Power down mode detected. Hard resetting");
reset_pin_->pin_mode(gpio::FLAG_OUTPUT); // Now set the resetPowerDownPin as digital output.
reset_pin_->digital_write(false); // Make sure we have a clean LOW state.
delayMicroseconds(2); // 8.8.1 Reset timing requirements says about 100ns. Let us be generous: 2μsl
@@ -101,7 +101,7 @@ void RC522::dump_config() {
case NONE:
break;
case RESET_FAILED:
ESP_LOGE(TAG, "Reset command failed!");
ESP_LOGE(TAG, "Reset command failed");
break;
}
@@ -292,7 +292,7 @@ void RC522::pcd_reset_() {
return;
if (reset_count_ == RESET_COUNT) {
ESP_LOGI(TAG, "Soft reset...");
ESP_LOGI(TAG, "Soft reset");
// Issue the SoftReset command.
pcd_write_register(COMMAND_REG, PCD_SOFT_RESET);
}
@@ -300,14 +300,14 @@ void RC522::pcd_reset_() {
// Expect the PowerDown bit in CommandReg to be cleared (max 3x50ms)
if ((pcd_read_register(COMMAND_REG) & (1 << 4)) == 0) {
reset_count_ = 0;
ESP_LOGI(TAG, "Device online.");
ESP_LOGI(TAG, "Device online");
// Wait for initialize
reset_timeout_ = millis();
return;
}
if (--reset_count_ == 0) {
ESP_LOGE(TAG, "Unable to reset RC522.");
ESP_LOGE(TAG, "Unable to reset");
this->error_code_ = RESET_FAILED;
mark_failed();
}

View File

@@ -15,7 +15,7 @@ void RemoteTransmitterComponent::setup() {
}
void RemoteTransmitterComponent::dump_config() {
ESP_LOGCONFIG(TAG, "Remote Transmitter...");
ESP_LOGCONFIG(TAG, "Remote Transmitter:");
ESP_LOGCONFIG(TAG, " Carrier Duty: %u%%", this->carrier_duty_percent_);
LOG_PIN(" Pin: ", this->pin_);
}
@@ -72,7 +72,7 @@ void RemoteTransmitterComponent::space_(uint32_t usec) {
}
void RemoteTransmitterComponent::send_internal(uint32_t send_times, uint32_t send_wait) {
ESP_LOGD(TAG, "Sending remote code...");
ESP_LOGD(TAG, "Sending remote code");
uint32_t on_time, off_time;
this->calculate_on_off_time_(this->temp_.get_carrier_frequency(), &on_time, &off_time);
this->target_time_ = 0;

View File

@@ -15,7 +15,7 @@ void RemoteTransmitterComponent::setup() {
}
void RemoteTransmitterComponent::dump_config() {
ESP_LOGCONFIG(TAG, "Remote Transmitter...");
ESP_LOGCONFIG(TAG, "Remote Transmitter:");
ESP_LOGCONFIG(TAG, " Carrier Duty: %u%%", this->carrier_duty_percent_);
LOG_PIN(" Pin: ", this->pin_);
}
@@ -74,7 +74,7 @@ void RemoteTransmitterComponent::space_(uint32_t usec) {
}
void RemoteTransmitterComponent::send_internal(uint32_t send_times, uint32_t send_wait) {
ESP_LOGD(TAG, "Sending remote code...");
ESP_LOGD(TAG, "Sending remote code");
uint32_t on_time, off_time;
this->calculate_on_off_time_(this->temp_.get_carrier_frequency(), &on_time, &off_time);
this->target_time_ = 0;

View File

@@ -9,7 +9,7 @@ namespace restart {
static const char *const TAG = "restart.button";
void RestartButton::press_action() {
ESP_LOGI(TAG, "Restarting device...");
ESP_LOGI(TAG, "Restarting device");
// Let MQTT settle a bit
delay(100); // NOLINT
App.safe_reboot();

View File

@@ -13,7 +13,7 @@ void RestartSwitch::write_state(bool state) {
this->publish_state(false);
if (state) {
ESP_LOGI(TAG, "Restarting device...");
ESP_LOGI(TAG, "Restarting device");
// Let MQTT settle a bit
delay(100); // NOLINT
App.safe_reboot();

View File

@@ -87,7 +87,7 @@ class RP2040Preferences : public ESPPreferences {
RP2040Preferences() : eeprom_sector_(&_EEPROM_start) {}
void setup() {
s_flash_storage = new uint8_t[RP2040_FLASH_STORAGE_SIZE]; // NOLINT
ESP_LOGVV(TAG, "Loading preferences from flash...");
ESP_LOGVV(TAG, "Loading preferences from flash");
memcpy(s_flash_storage, this->eeprom_sector_, RP2040_FLASH_STORAGE_SIZE);
}

View File

@@ -138,7 +138,7 @@ void RP2040PIOLEDStripLightOutput::setup() {
}
void RP2040PIOLEDStripLightOutput::write_state(light::LightState *state) {
ESP_LOGVV(TAG, "Writing state...");
ESP_LOGVV(TAG, "Writing state");
if (this->is_failed()) {
ESP_LOGW(TAG, "Light is in failed state, not writing state.");

View File

@@ -533,7 +533,7 @@ void MR24HPC1Component::r24_frame_parse_work_status_(uint8_t *data) {
this->custom_mode_number_->publish_state(0);
}
if (this->custom_mode_end_text_sensor_ != nullptr) {
this->custom_mode_end_text_sensor_->publish_state("Setup in progress...");
this->custom_mode_end_text_sensor_->publish_state("Setup in progress");
}
} else if (data[FRAME_COMMAND_WORD_INDEX] == 0x81) {
ESP_LOGD(TAG, "Reply: get radar init status 0x%02X", data[FRAME_DATA_INDEX]);

View File

@@ -101,7 +101,7 @@ void ShellyDimmer::setup() {
this->pin_nrst_->setup();
this->pin_boot0_->setup();
ESP_LOGI(TAG, "Initializing Shelly Dimmer...");
ESP_LOGI(TAG, "Initializing");
this->handle_firmware();

View File

@@ -17,7 +17,7 @@ static const char *const TAG = "shutdown.button";
void ShutdownButton::dump_config() { LOG_BUTTON("", "Shutdown Button", this); }
void ShutdownButton::press_action() {
ESP_LOGI(TAG, "Shutting down...");
ESP_LOGI(TAG, "Shutting down");
// Let MQTT settle a bit
delay(100); // NOLINT
App.run_safe_shutdown_hooks();

View File

@@ -21,7 +21,7 @@ void ShutdownSwitch::write_state(bool state) {
this->publish_state(false);
if (state) {
ESP_LOGI(TAG, "Shutting down...");
ESP_LOGI(TAG, "Shutting down");
delay(100); // NOLINT
App.run_safe_shutdown_hooks();

View File

@@ -28,7 +28,7 @@ void Sim800LComponent::update() {
this->state_ = STATE_DIALING1;
} else if (this->registered_ && this->connect_pending_) {
this->connect_pending_ = false;
ESP_LOGI(TAG, "Connecting...");
ESP_LOGI(TAG, "Connecting");
this->send_cmd_("ATA");
this->state_ = STATE_ATA_SENT;
} else if (this->registered_ && this->send_ussd_pending_) {
@@ -36,7 +36,7 @@ void Sim800LComponent::update() {
this->state_ = STATE_SEND_USSD1;
} else if (this->registered_ && this->disconnect_pending_) {
this->disconnect_pending_ = false;
ESP_LOGI(TAG, "Disconnecting...");
ESP_LOGI(TAG, "Disconnecting");
this->send_cmd_("ATH");
} else if (this->registered_ && this->call_state_ != 6) {
send_cmd_("AT+CLCC");

View File

@@ -13,7 +13,7 @@ void ST7567::setup() {
}
void ST7567::display_init_() {
ESP_LOGD(TAG, "Initializing ST7567 display...");
ESP_LOGD(TAG, "Initializing display");
this->display_init_registers_();
this->clear();
this->write_display_data();
@@ -42,7 +42,7 @@ void ST7567::display_init_registers_() {
}
void ST7567::display_sw_refresh_() {
ESP_LOGD(TAG, "Performing refresh sequence...");
ESP_LOGD(TAG, "Performing refresh sequence");
this->command(ST7567_SW_REFRESH);
this->display_init_registers_();
}

View File

@@ -129,7 +129,7 @@ void HOT ST7920::draw_absolute_pixel_internal(int x, int y, Color color) {
}
void ST7920::display_init_() {
ESP_LOGD(TAG, "Initializing display...");
ESP_LOGD(TAG, "Initializing display");
this->command_(LCD_BASIC); // 8bit mode
this->command_(LCD_BASIC); // 8bit mode
this->command_(LCD_CLS); // clear screen

View File

@@ -10,7 +10,7 @@ static const char *const TAG = "sx1509";
void SX1509Component::setup() {
ESP_LOGCONFIG(TAG, "Running setup");
ESP_LOGV(TAG, " Resetting devices...");
ESP_LOGV(TAG, " Resetting devices");
if (!this->write_byte(REG_RESET, 0x12)) {
this->mark_failed();
return;

View File

@@ -43,7 +43,6 @@ void TEM3200Component::setup() {
this->status_set_warning();
break;
}
ESP_LOGCONFIG(TAG, " Success...");
}
void TEM3200Component::dump_config() {

View File

@@ -537,7 +537,7 @@ void ThermostatClimate::switch_to_supplemental_action_(climate::ClimateAction ac
default:
return;
}
ESP_LOGVV(TAG, "Updating supplemental action...");
ESP_LOGVV(TAG, "Updating supplemental action");
this->supplemental_action_ = action;
this->trigger_supplemental_action_();
}

View File

@@ -73,7 +73,7 @@ static const uint8_t LDR_GRPPWM = 0x03;
void TLC59208FOutput::setup() {
ESP_LOGCONFIG(TAG, "Running setup");
ESP_LOGV(TAG, " Resetting all devices on the bus...");
ESP_LOGV(TAG, " Resetting all devices on the bus");
// Reset all devices on the bus
if (this->bus_->write(TLC59208F_SWRST_ADDR >> 1, TLC59208F_SWRST_SEQ, 2) != i2c::ERROR_OK) {

View File

@@ -20,7 +20,7 @@ static const uint8_t TM1638_UNKNOWN_CHAR = 0b11111111;
static const uint8_t TM1638_SHIFT_DELAY = 4; // clock pause between commands, default 4ms
void TM1638Component::setup() {
ESP_LOGD(TAG, "Setting up TM1638...");
ESP_LOGCONFIG(TAG, "Running setup");
this->clk_pin_->setup(); // OUTPUT
this->dio_pin_->setup(); // OUTPUT

View File

@@ -44,7 +44,7 @@ float Tx20Component::get_setup_priority() const { return setup_priority::DATA; }
std::string Tx20Component::get_wind_cardinal_direction() const { return this->wind_cardinal_direction_; }
void Tx20Component::decode_and_publish_() {
ESP_LOGVV(TAG, "Decode Tx20...");
ESP_LOGVV(TAG, "Decode Tx20");
std::string string_buffer;
std::string string_buffer_2;

View File

@@ -7,7 +7,7 @@ namespace uart {
static const char *const TAG = "uart.button";
void UARTButton::press_action() {
ESP_LOGD(TAG, "'%s': Sending data...", this->get_name().c_str());
ESP_LOGD(TAG, "'%s': Sending data", this->get_name().c_str());
this->write_array(this->data_.data(), this->data_.size());
}

View File

@@ -19,11 +19,11 @@ void UARTSwitch::loop() {
void UARTSwitch::write_command_(bool state) {
if (state && !this->data_on_.empty()) {
ESP_LOGD(TAG, "'%s': Sending on data...", this->get_name().c_str());
ESP_LOGD(TAG, "'%s': Sending on data", this->get_name().c_str());
this->write_array(this->data_on_.data(), this->data_on_.size());
}
if (!state && !this->data_off_.empty()) {
ESP_LOGD(TAG, "'%s': Sending off data...", this->get_name().c_str());
ESP_LOGD(TAG, "'%s': Sending off data", this->get_name().c_str());
this->write_array(this->data_off_.data(), this->data_off_.size());
}
}

View File

@@ -191,7 +191,7 @@ bool ESP32ArduinoUARTComponent::read_array(uint8_t *data, size_t len) {
int ESP32ArduinoUARTComponent::available() { return this->hw_serial_->available(); }
void ESP32ArduinoUARTComponent::flush() {
ESP_LOGVV(TAG, " Flushing...");
ESP_LOGVV(TAG, " Flushing");
this->hw_serial_->flush();
}

View File

@@ -99,7 +99,7 @@ void ESP8266UartComponent::setup() {
}
void ESP8266UartComponent::load_settings(bool dump_config) {
ESP_LOGCONFIG(TAG, "Loading UART bus settings...");
ESP_LOGCONFIG(TAG, "Loading UART bus settings");
if (this->hw_serial_ != nullptr) {
SerialConfig config = static_cast<SerialConfig>(get_config());
this->hw_serial_->begin(this->baud_rate_, config);
@@ -193,7 +193,7 @@ int ESP8266UartComponent::available() {
}
}
void ESP8266UartComponent::flush() {
ESP_LOGVV(TAG, " Flushing...");
ESP_LOGVV(TAG, " Flushing");
if (this->hw_serial_ != nullptr) {
this->hw_serial_->flush();
} else {

View File

@@ -234,7 +234,7 @@ int IDFUARTComponent::available() {
}
void IDFUARTComponent::flush() {
ESP_LOGVV(TAG, " Flushing...");
ESP_LOGVV(TAG, " Flushing");
xSemaphoreTake(this->lock_, portMAX_DELAY);
uart_wait_tx_done(this->uart_num_, portMAX_DELAY);
xSemaphoreGive(this->lock_);

View File

@@ -109,7 +109,7 @@ HostUartComponent::~HostUartComponent() {
}
void HostUartComponent::setup() {
ESP_LOGCONFIG(TAG, "Opening UART port...");
ESP_LOGCONFIG(TAG, "Opening UART port");
speed_t baud = get_baud(this->baud_rate_);
if (baud == B0) {
ESP_LOGE(TAG, "Unsupported baud rate: %d", this->baud_rate_);
@@ -283,7 +283,7 @@ void HostUartComponent::flush() {
return;
}
tcflush(this->file_descriptor_, TCIOFLUSH);
ESP_LOGV(TAG, " Flushing...");
ESP_LOGV(TAG, " Flushing");
}
void HostUartComponent::update_error_(const std::string &error) {

View File

@@ -145,7 +145,7 @@ bool LibreTinyUARTComponent::read_array(uint8_t *data, size_t len) {
int LibreTinyUARTComponent::available() { return this->serial_->available(); }
void LibreTinyUARTComponent::flush() {
ESP_LOGVV(TAG, " Flushing...");
ESP_LOGVV(TAG, " Flushing");
this->serial_->flush();
}

View File

@@ -174,7 +174,7 @@ bool RP2040UartComponent::read_array(uint8_t *data, size_t len) {
}
int RP2040UartComponent::available() { return this->serial_->available(); }
void RP2040UartComponent::flush() {
ESP_LOGVV(TAG, " Flushing...");
ESP_LOGVV(TAG, " Flushing");
this->serial_->flush();
}

View File

@@ -204,7 +204,7 @@ void VoiceAssistant::loop() {
break;
}
case State::START_PIPELINE: {
ESP_LOGD(TAG, "Requesting start...");
ESP_LOGD(TAG, "Requesting start");
uint32_t flags = 0;
if (!this->continue_conversation_ && this->use_wake_word_)
flags |= api::enums::VOICE_ASSISTANT_REQUEST_USE_WAKE_WORD;
@@ -577,7 +577,7 @@ void VoiceAssistant::signal_stop_() {
if (this->api_client_ == nullptr) {
return;
}
ESP_LOGD(TAG, "Signaling stop...");
ESP_LOGD(TAG, "Signaling stop");
api::VoiceAssistantRequest msg;
msg.start = false;
this->api_client_->send_voice_assistant_request(msg);

View File

@@ -30,7 +30,7 @@ void WakeOnLanButton::press_action() {
ESP_LOGW(TAG, "Network not connected");
return;
}
ESP_LOGI(TAG, "Sending Wake-on-LAN Packet...");
ESP_LOGI(TAG, "Sending Wake-on-LAN Packet");
#if defined(USE_SOCKET_IMPL_BSD_SOCKETS) || defined(USE_SOCKET_IMPL_LWIP_SOCKETS)
struct sockaddr_storage saddr {};
auto addr_len =

View File

@@ -112,7 +112,7 @@ void WeikaiComponent::loop() {
transferred += child->xfer_fifo_to_buffer_();
}
if (transferred > 0) {
ESP_LOGV(TAG, "we transferred %d bytes from fifo to buffer...", transferred);
ESP_LOGV(TAG, "transferred %d bytes from fifo to buffer", transferred);
}
#ifdef TEST_COMPONENT
@@ -121,8 +121,8 @@ void WeikaiComponent::loop() {
uint32_t time = 0;
if (test_mode_ == 1) { // test component in loopback
ESP_LOGI(TAG, "Component loop %" PRIu32 " for %s : %" PRIu32 " ms since last call ...", loop_count++,
this->get_name(), millis() - loop_time);
ESP_LOGI(TAG, "Component loop %" PRIu32 " for %s : %" PRIu32 " ms since last call", loop_count++, this->get_name(),
millis() - loop_time);
loop_time = millis();
char message[64];
elapsed_ms(time); // set time to now
@@ -134,14 +134,14 @@ void WeikaiComponent::loop() {
uint32_t const start_time = millis();
while (children_[i]->tx_fifo_is_not_empty_()) { // wait until buffer empty
if (millis() - start_time > 1500) {
ESP_LOGE(TAG, "timeout while flushing - %d bytes left in buffer...", children_[i]->tx_in_fifo_());
ESP_LOGE(TAG, "timeout while flushing - %d bytes left in buffer", children_[i]->tx_in_fifo_());
break;
}
yield(); // reschedule our thread to avoid blocking
}
bool status = children_[i]->uart_receive_test_(message);
ESP_LOGI(TAG, "Test %s => send/received %u bytes %s - execution time %" PRIu32 " ms...", message,
RING_BUFFER_SIZE, status ? "correctly" : "with error", elapsed_ms(time));
ESP_LOGI(TAG, "Test %s => send/received %u bytes %s - execution time %" PRIu32 " ms", message, RING_BUFFER_SIZE,
status ? "correctly" : "with error", elapsed_ms(time));
}
}
@@ -255,10 +255,10 @@ std::string WeikaiGPIOPin::dump_summary() const {
// The WeikaiChannel methods
///////////////////////////////////////////////////////////////////////////////
void WeikaiChannel::setup_channel() {
ESP_LOGCONFIG(TAG, " Setting up UART %s:%s ...", this->parent_->get_name(), this->get_channel_name());
ESP_LOGCONFIG(TAG, " Setting up UART %s:%s", this->parent_->get_name(), this->get_channel_name());
// we enable transmit and receive on this channel
if (this->check_channel_down()) {
ESP_LOGCONFIG(TAG, " Error channel %s not working...", this->get_channel_name());
ESP_LOGCONFIG(TAG, " Error channel %s not working", this->get_channel_name());
}
this->reset_fifo_();
this->receive_buffer_.clear();
@@ -267,7 +267,7 @@ void WeikaiChannel::setup_channel() {
}
void WeikaiChannel::dump_channel() {
ESP_LOGCONFIG(TAG, " UART %s ...", this->get_channel_name());
ESP_LOGCONFIG(TAG, " UART %s", this->get_channel_name());
ESP_LOGCONFIG(TAG, " Baud rate: %" PRIu32 " Bd", this->baud_rate_);
ESP_LOGCONFIG(TAG, " Data bits: %u", this->data_bits_);
ESP_LOGCONFIG(TAG, " Stop bits: %u", this->stop_bits_);
@@ -407,7 +407,7 @@ bool WeikaiChannel::read_array(uint8_t *buffer, size_t length) {
bool status = true;
auto available = this->receive_buffer_.count();
if (length > available) {
ESP_LOGW(TAG, "read_array: buffer underflow requested %d bytes only %d bytes available...", length, available);
ESP_LOGW(TAG, "read_array: buffer underflow requested %d bytes only %d bytes available", length, available);
length = available;
status = false;
}
@@ -422,7 +422,7 @@ bool WeikaiChannel::read_array(uint8_t *buffer, size_t length) {
void WeikaiChannel::write_array(const uint8_t *buffer, size_t length) {
if (length > XFER_MAX_SIZE) {
ESP_LOGE(TAG, "Write_array: invalid call - requested %d bytes but max size %d ...", length, XFER_MAX_SIZE);
ESP_LOGE(TAG, "Write_array: invalid call - requested %d bytes but max size %d", length, XFER_MAX_SIZE);
length = XFER_MAX_SIZE;
}
this->reg(0).write_fifo(const_cast<uint8_t *>(buffer), length);
@@ -432,7 +432,7 @@ void WeikaiChannel::flush() {
uint32_t const start_time = millis();
while (this->tx_fifo_is_not_empty_()) { // wait until buffer empty
if (millis() - start_time > 200) {
ESP_LOGW(TAG, "WARNING flush timeout - still %d bytes not sent after 200 ms...", this->tx_in_fifo_());
ESP_LOGW(TAG, "WARNING flush timeout - still %d bytes not sent after 200 ms", this->tx_in_fifo_());
return;
}
yield(); // reschedule our thread to avoid blocking
@@ -509,7 +509,7 @@ void WeikaiChannel::uart_send_test_(char *message) {
this->flush();
to_send -= XFER_MAX_SIZE;
}
ESP_LOGV(TAG, "%s => sent %d bytes - exec time %d µs ...", message, RING_BUFFER_SIZE, micros() - start_exec);
ESP_LOGV(TAG, "%s => sent %d bytes - exec time %d µs", message, RING_BUFFER_SIZE, micros() - start_exec);
}
/// @brief test read_array method
@@ -526,7 +526,7 @@ bool WeikaiChannel::uart_receive_test_(char *message) {
while (XFER_MAX_SIZE > this->available()) {
this->xfer_fifo_to_buffer_();
if (millis() - start_time > 1500) {
ESP_LOGE(TAG, "uart_receive_test_() timeout: only %d bytes received...", this->available());
ESP_LOGE(TAG, "uart_receive_test_() timeout: only %d bytes received", this->available());
break;
}
yield(); // reschedule our thread to avoid blocking
@@ -538,20 +538,20 @@ bool WeikaiChannel::uart_receive_test_(char *message) {
uint8_t peek_value = 0;
this->peek_byte(&peek_value);
if (peek_value != 0) {
ESP_LOGE(TAG, "Peek first byte value error...");
ESP_LOGE(TAG, "Peek first byte value error");
status = false;
}
for (size_t i = 0; i < RING_BUFFER_SIZE; i++) {
if (buffer[i] != i % XFER_MAX_SIZE) {
ESP_LOGE(TAG, "Read buffer contains error...b=%x i=%x", buffer[i], i % XFER_MAX_SIZE);
ESP_LOGE(TAG, "Read buffer contains error b=%x i=%x", buffer[i], i % XFER_MAX_SIZE);
print_buffer(buffer);
status = false;
break;
}
}
ESP_LOGV(TAG, "%s => received %d bytes status %s - exec time %d µs ...", message, received, status ? "OK" : "ERROR",
ESP_LOGV(TAG, "%s => received %d bytes status %s - exec time %d µs", message, received, status ? "OK" : "ERROR",
micros() - start_exec);
return status;
}

View File

@@ -96,7 +96,7 @@ void WeikaiRegisterI2C::read_fifo(uint8_t *data, size_t length) const {
#endif
} else { // error
this->comp_->status_set_warning();
ESP_LOGE(TAG, "WeikaiRegisterI2C::read_fifo() @%02X reg=N/A ch=%d I2C_code:%d len=%d buf=%02X...", address,
ESP_LOGE(TAG, "WeikaiRegisterI2C::read_fifo() @%02X reg=N/A ch=%d I2C_code:%d len=%d buf=%02X", address,
this->channel_, (int) error, length, data[0]);
}
}
@@ -131,8 +131,8 @@ void WeikaiRegisterI2C::write_fifo(uint8_t *data, size_t length) {
#endif
} else { // error
this->comp_->status_set_warning();
ESP_LOGE(TAG, "WK2168Reg::write_fifo() @%02X reg=N/A, ch=%d I2C_code:%d len=%d, buf=%02X...", address,
this->channel_, (int) error, length, data[0]);
ESP_LOGE(TAG, "WK2168Reg::write_fifo() @%02X reg=N/A, ch=%d I2C_code:%d len=%d, buf=%02X", address, this->channel_,
(int) error, length, data[0]);
}
}

View File

@@ -156,7 +156,7 @@ void WeikaiRegisterSPI::write_fifo(uint8_t *data, size_t length) {
///////////////////////////////////////////////////////////////////////////////
void WeikaiComponentSPI::setup() {
using namespace weikai;
ESP_LOGCONFIG(TAG, "Running setup for '%s' with %d UARTs...", this->get_name(), this->children_.size());
ESP_LOGCONFIG(TAG, "Running setup for '%s' with %d UARTs", this->get_name(), this->children_.size());
this->spi_setup();
// enable all channels
this->reg(WKREG_GENA, 0) = GENA_C1EN | GENA_C2EN | GENA_C3EN | GENA_C4EN;

View File

@@ -260,7 +260,7 @@ void WiFiComponent::setup_ap_config_() {
this->ap_.set_ssid(name);
}
ESP_LOGCONFIG(TAG, "Setting up AP...");
ESP_LOGCONFIG(TAG, "Setting up AP");
ESP_LOGCONFIG(TAG, " AP SSID: '%s'", this->ap_.get_ssid().c_str());
ESP_LOGCONFIG(TAG, " AP Password: '%s'", this->ap_.get_password().c_str());
@@ -479,7 +479,7 @@ bool WiFiComponent::is_disabled() { return this->state_ == WIFI_COMPONENT_STATE_
void WiFiComponent::start_scanning() {
this->action_started_ = millis();
ESP_LOGD(TAG, "Starting scan...");
ESP_LOGD(TAG, "Starting scan");
this->wifi_scan_start_(this->passive_scan_);
this->state_ = WIFI_COMPONENT_STATE_STA_SCANNING;
}
@@ -623,7 +623,7 @@ void WiFiComponent::check_connecting_finished() {
captive_portal::global_captive_portal->end();
}
#endif
ESP_LOGD(TAG, "Disabling AP...");
ESP_LOGD(TAG, "Disabling AP");
this->wifi_mode_({}, false);
}
#ifdef USE_IMPROV
@@ -687,14 +687,14 @@ 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 WiFi adapter");
this->wifi_mode_(false, {});
delay(100); // NOLINT
this->num_retried_ = 0;
this->retry_hidden_ = false;
} else {
// Try hidden networks after 3 failed retries
ESP_LOGD(TAG, "Retrying with hidden networks...");
ESP_LOGD(TAG, "Retrying with hidden networks");
this->retry_hidden_ = true;
this->num_retried_++;
}

View File

@@ -590,7 +590,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
// 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) {
ESP_LOGW(TAG, "Potential Authmode downgrade detected, disconnecting...");
ESP_LOGW(TAG, "Potential Authmode downgrade detected, disconnecting");
// we can't call retry_connect() from this context, so disconnect immediately
// and notify main thread with error_from_callback_
err_t err = esp_wifi_disconnect();

View File

@@ -525,7 +525,7 @@ void WiFiComponent::wifi_event_callback(System_Event_t *event) {
// Mitigate CVE-2020-12638
// https://lbsfilm.at/blog/wpa2-authenticationmode-downgrade-in-espressif-microprocessors
if (it.old_mode != AUTH_OPEN && it.new_mode == AUTH_OPEN) {
ESP_LOGW(TAG, "Potential Authmode downgrade detected, disconnecting...");
ESP_LOGW(TAG, "Potential Authmode downgrade detected, disconnecting");
// we can't call retry_connect() from this context, so disconnect immediately
// and notify main thread with error_from_callback_
wifi_station_disconnect();

View File

@@ -315,7 +315,7 @@ void WiFiComponent::wifi_event_callback_(esphome_wifi_event_id_t event, esphome_
// 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) {
ESP_LOGW(TAG, "Potential Authmode downgrade detected, disconnecting...");
ESP_LOGW(TAG, "Potential Authmode downgrade detected, disconnecting");
// we can't call retry_connect() from this context, so disconnect immediately
// and notify main thread with error_from_callback_
WiFi.disconnect();

View File

@@ -69,7 +69,7 @@ void XGZP68XXComponent::update() {
}
void XGZP68XXComponent::setup() {
ESP_LOGD(TAG, "Setting up XGZP68xx...");
ESP_LOGCONFIG(TAG, "Running setup");
uint8_t config;
// Display some sample bits to confirm we are talking to the sensor
@@ -79,12 +79,12 @@ void XGZP68XXComponent::setup() {
}
void XGZP68XXComponent::dump_config() {
ESP_LOGCONFIG(TAG, "XGZP68xx");
ESP_LOGCONFIG(TAG, "XGZP68xx:");
LOG_SENSOR(" ", "Temperature: ", this->temperature_sensor_);
LOG_SENSOR(" ", "Pressure: ", this->pressure_sensor_);
LOG_I2C_DEVICE(this);
if (this->is_failed()) {
ESP_LOGE(TAG, " Connection with XGZP68xx failed!");
ESP_LOGE(TAG, " Connection failed");
}
LOG_UPDATE_INTERVAL(this);
}

View File

@@ -45,8 +45,8 @@ void Application::register_component_(Component *comp) {
this->components_.push_back(comp);
}
void Application::setup() {
ESP_LOGI(TAG, "Running through setup()...");
ESP_LOGV(TAG, "Sorting components by setup priority...");
ESP_LOGI(TAG, "Running through setup()");
ESP_LOGV(TAG, "Sorting components by setup priority");
std::stable_sort(this->components_.begin(), this->components_.end(), [](const Component *a, const Component *b) {
return a->get_actual_setup_priority() > b->get_actual_setup_priority();
});
@@ -215,14 +215,14 @@ void IRAM_ATTR HOT Application::feed_wdt(uint32_t time) {
}
}
void Application::reboot() {
ESP_LOGI(TAG, "Forcing a reboot...");
ESP_LOGI(TAG, "Forcing a reboot");
for (auto it = this->components_.rbegin(); it != this->components_.rend(); ++it) {
(*it)->on_shutdown();
}
arch_restart();
}
void Application::safe_reboot() {
ESP_LOGI(TAG, "Rebooting safely...");
ESP_LOGI(TAG, "Rebooting safely");
run_safe_shutdown_hooks();
arch_restart();
}