IDF 5 fixes for various components from test1.yaml (#5451)

This commit is contained in:
Keith Burzinski 2023-10-18 01:33:36 -05:00 committed by GitHub
parent 8ef743f25e
commit cdc4f7f59b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
82 changed files with 173 additions and 97 deletions

View File

@ -22,7 +22,7 @@ void binary_sensor::MultiClickTrigger::on_state_(bool state) {
// Start matching
MultiClickTriggerEvent evt = this->timing_[0];
if (evt.state == state) {
ESP_LOGV(TAG, "START min=%u max=%u", evt.min_length, evt.max_length);
ESP_LOGV(TAG, "START min=%" PRIu32 " max=%" PRIu32, evt.min_length, evt.max_length);
ESP_LOGV(TAG, "Multi Click: Starting multi click action!");
this->at_index_ = 1;
if (this->timing_.size() == 1 && evt.max_length == 4294967294UL) {
@ -51,15 +51,15 @@ void binary_sensor::MultiClickTrigger::on_state_(bool state) {
MultiClickTriggerEvent evt = this->timing_[*this->at_index_];
if (evt.max_length != 4294967294UL) {
ESP_LOGV(TAG, "A i=%u min=%u max=%u", *this->at_index_, evt.min_length, evt.max_length); // NOLINT
ESP_LOGV(TAG, "A i=%u min=%" PRIu32 " max=%" PRIu32, *this->at_index_, evt.min_length, evt.max_length); // NOLINT
this->schedule_is_valid_(evt.min_length);
this->schedule_is_not_valid_(evt.max_length);
} else if (*this->at_index_ + 1 != this->timing_.size()) {
ESP_LOGV(TAG, "B i=%u min=%u", *this->at_index_, evt.min_length); // NOLINT
ESP_LOGV(TAG, "B i=%u min=%" PRIu32, *this->at_index_, evt.min_length); // NOLINT
this->cancel_timeout("is_not_valid");
this->schedule_is_valid_(evt.min_length);
} else {
ESP_LOGV(TAG, "C i=%u min=%u", *this->at_index_, evt.min_length); // NOLINT
ESP_LOGV(TAG, "C i=%u min=%" PRIu32, *this->at_index_, evt.min_length); // NOLINT
this->is_valid_ = false;
this->cancel_timeout("is_not_valid");
this->set_timeout("trigger", evt.min_length, [this]() { this->trigger_(); });
@ -68,7 +68,8 @@ 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 %u 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

@ -1,5 +1,6 @@
#pragma once
#include <cinttypes>
#include <utility>
#include <vector>

View File

@ -16,9 +16,9 @@ void Canbus::setup() {
void Canbus::dump_config() {
if (this->use_extended_id_) {
ESP_LOGCONFIG(TAG, "config extended id=0x%08x", this->can_id_);
ESP_LOGCONFIG(TAG, "config extended id=0x%08" PRIx32, this->can_id_);
} else {
ESP_LOGCONFIG(TAG, "config standard id=0x%03x", this->can_id_);
ESP_LOGCONFIG(TAG, "config standard id=0x%03" PRIx32, this->can_id_);
}
}
@ -28,9 +28,11 @@ void Canbus::send_data(uint32_t can_id, bool use_extended_id, bool remote_transm
uint8_t size = static_cast<uint8_t>(data.size());
if (use_extended_id) {
ESP_LOGD(TAG, "send extended id=0x%08x rtr=%s size=%d", can_id, TRUEFALSE(remote_transmission_request), size);
ESP_LOGD(TAG, "send extended id=0x%08" PRIx32 " rtr=%s size=%d", can_id, TRUEFALSE(remote_transmission_request),
size);
} else {
ESP_LOGD(TAG, "send standard id=0x%03x rtr=%s size=%d", can_id, TRUEFALSE(remote_transmission_request), size);
ESP_LOGD(TAG, "send standard id=0x%03" PRIx32 " rtr=%s size=%d", can_id, TRUEFALSE(remote_transmission_request),
size);
}
if (size > CAN_MAX_DATA_LENGTH)
size = CAN_MAX_DATA_LENGTH;
@ -63,10 +65,10 @@ void Canbus::loop() {
while (this->read_message(&can_message) == canbus::ERROR_OK) {
message_counter++;
if (can_message.use_extended_id) {
ESP_LOGD(TAG, "received can message (#%d) extended can_id=0x%x size=%d", message_counter, can_message.can_id,
can_message.can_data_length_code);
ESP_LOGD(TAG, "received can message (#%d) extended can_id=0x%" PRIx32 " size=%d", message_counter,
can_message.can_id, can_message.can_data_length_code);
} else {
ESP_LOGD(TAG, "received can message (#%d) std can_id=0x%x size=%d", message_counter, can_message.can_id,
ESP_LOGD(TAG, "received can message (#%d) std can_id=0x%" PRIx32 " size=%d", message_counter, can_message.can_id,
can_message.can_data_length_code);
}

View File

@ -4,6 +4,7 @@
#include "esphome/core/component.h"
#include "esphome/core/optional.h"
#include <cinttypes>
#include <vector>
namespace esphome {

View File

@ -121,7 +121,7 @@ bool LgIrClimate::on_receive(remote_base::RemoteReceiveData data) {
}
}
ESP_LOGD(TAG, "Decoded 0x%02X", remote_state);
ESP_LOGD(TAG, "Decoded 0x%02" PRIX32, remote_state);
if ((remote_state & 0xFF00000) != 0x8800000)
return false;
@ -173,7 +173,7 @@ bool LgIrClimate::on_receive(remote_base::RemoteReceiveData data) {
}
void LgIrClimate::transmit_(uint32_t value) {
calc_checksum_(value);
ESP_LOGD(TAG, "Sending climate_lg_ir code: 0x%02X", value);
ESP_LOGD(TAG, "Sending climate_lg_ir code: 0x%02" PRIX32, value);
auto transmit = this->transmitter_->transmit();
auto *data = transmit.get_data();

View File

@ -2,6 +2,8 @@
#include "esphome/components/climate_ir/climate_ir.h"
#include <cinttypes>
namespace esphome {
namespace climate_ir_lg {

View File

@ -101,7 +101,7 @@ void CoolixClimate::transmit_state() {
}
}
}
ESP_LOGV(TAG, "Sending coolix code: 0x%06X", remote_state);
ESP_LOGV(TAG, "Sending coolix code: 0x%06" PRIX32, remote_state);
auto transmit = this->transmitter_->transmit();
auto *data = transmit.get_data();
@ -115,7 +115,7 @@ bool CoolixClimate::on_coolix(climate::Climate *parent, remote_base::RemoteRecei
return false;
// Decoded remote state y 3 bytes long code.
uint32_t remote_state = (*decoded).second;
ESP_LOGV(TAG, "Decoded 0x%06X", remote_state);
ESP_LOGV(TAG, "Decoded 0x%06" PRIX32, remote_state);
if ((remote_state & 0xFF0000) != 0xB20000)
return false;

View File

@ -2,6 +2,8 @@
#include "esphome/components/climate_ir/climate_ir.h"
#include <cinttypes>
namespace esphome {
namespace coolix {

View File

@ -86,7 +86,7 @@ void CS5460AComponent::hw_init_() {
}
uint32_t status = this->read_register_(REG_STATUS);
ESP_LOGCONFIG(TAG, " Version: %x", (status >> 6) & 7);
ESP_LOGCONFIG(TAG, " Version: %" PRIx32, (status >> 6) & 7);
this->write_register_(REG_CYCLE_COUNT, samples_);
this->write_register_(REG_PULSE_RATE, lroundf(pulse_freq_ * 32.0f));
@ -323,7 +323,7 @@ void CS5460AComponent::dump_config() {
ESP_LOGCONFIG(TAG, " Init status: %s",
state == COMPONENT_STATE_LOOP ? "OK" : (state == COMPONENT_STATE_FAILED ? "failed" : "other"));
LOG_PIN(" CS Pin: ", cs_);
ESP_LOGCONFIG(TAG, " Samples / cycle: %u", samples_);
ESP_LOGCONFIG(TAG, " Samples / cycle: %" PRIu32, samples_);
ESP_LOGCONFIG(TAG, " Phase offset: %i", phase_offset_);
ESP_LOGCONFIG(TAG, " PGA Gain: %s", pga_gain_ == CS5460A_PGA_GAIN_50X ? "50x" : "10x");
ESP_LOGCONFIG(TAG, " Current gain: %.5f", current_gain_);

View File

@ -5,6 +5,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/spi/spi.h"
#include <cinttypes>
namespace esphome {
namespace cs5460a {

View File

@ -39,7 +39,7 @@ void DeepSleepComponent::setup() {
const optional<uint32_t> run_duration = get_run_duration_();
if (run_duration.has_value()) {
ESP_LOGI(TAG, "Scheduling Deep Sleep to start in %u ms", *run_duration);
ESP_LOGI(TAG, "Scheduling Deep Sleep to start in %" PRIu32 " ms", *run_duration);
this->set_timeout(*run_duration, [this]() { this->begin_sleep(); });
} else {
ESP_LOGD(TAG, "Not scheduling Deep Sleep, as no run duration is configured.");
@ -49,19 +49,20 @@ void DeepSleepComponent::dump_config() {
ESP_LOGCONFIG(TAG, "Setting up Deep Sleep...");
if (this->sleep_duration_.has_value()) {
uint32_t duration = *this->sleep_duration_ / 1000;
ESP_LOGCONFIG(TAG, " Sleep Duration: %u ms", duration);
ESP_LOGCONFIG(TAG, " Sleep Duration: %" PRIu32 " ms", duration);
}
if (this->run_duration_.has_value()) {
ESP_LOGCONFIG(TAG, " Run Duration: %u ms", *this->run_duration_);
ESP_LOGCONFIG(TAG, " Run Duration: %" PRIu32 " ms", *this->run_duration_);
}
#ifdef USE_ESP32
if (wakeup_pin_ != nullptr) {
LOG_PIN(" Wakeup Pin: ", this->wakeup_pin_);
}
if (this->wakeup_cause_to_run_duration_.has_value()) {
ESP_LOGCONFIG(TAG, " Default Wakeup Run Duration: %u ms", this->wakeup_cause_to_run_duration_->default_cause);
ESP_LOGCONFIG(TAG, " Touch Wakeup Run Duration: %u ms", this->wakeup_cause_to_run_duration_->touch_cause);
ESP_LOGCONFIG(TAG, " GPIO Wakeup Run Duration: %u ms", this->wakeup_cause_to_run_duration_->gpio_cause);
ESP_LOGCONFIG(TAG, " Default Wakeup Run Duration: %" PRIu32 " ms",
this->wakeup_cause_to_run_duration_->default_cause);
ESP_LOGCONFIG(TAG, " Touch Wakeup Run Duration: %" PRIu32 " ms", this->wakeup_cause_to_run_duration_->touch_cause);
ESP_LOGCONFIG(TAG, " GPIO Wakeup Run Duration: %" PRIu32 " ms", this->wakeup_cause_to_run_duration_->gpio_cause);
}
#endif
}

View File

@ -14,6 +14,8 @@
#include "esphome/core/time.h"
#endif
#include <cinttypes>
namespace esphome {
namespace deep_sleep {

View File

@ -3,6 +3,7 @@
#include "esphome/components/socket/socket.h"
#include "esphome/core/component.h"
#include <cinttypes>
#include <map>
#include <memory>
#include <set>

View File

@ -57,8 +57,8 @@ bool E131AddressableLightEffect::process_(int universe, const E131Packet &packet
std::min(it->size(), std::min(output_offset + get_lights_per_universe(), output_offset + packet.count - 1));
auto *input_data = packet.values + 1;
ESP_LOGV(TAG, "Applying data for '%s' on %d universe, for %d-%d.", get_name().c_str(), universe, output_offset,
output_end);
ESP_LOGV(TAG, "Applying data for '%s' on %d universe, for %" PRId32 "-%d.", get_name().c_str(), universe,
output_offset, output_end);
switch (channels_) {
case E131_MONO:

View File

@ -38,7 +38,7 @@ void HLW8012Component::dump_config() {
LOG_PIN(" SEL Pin: ", this->sel_pin_)
LOG_PIN(" CF Pin: ", this->cf_pin_)
LOG_PIN(" CF1 Pin: ", this->cf1_pin_)
ESP_LOGCONFIG(TAG, " Change measurement mode every %u", this->change_mode_every_);
ESP_LOGCONFIG(TAG, " Change measurement mode every %" PRIu32, this->change_mode_every_);
ESP_LOGCONFIG(TAG, " Current resistor: %.1f mΩ", this->current_resistor_ * 1000.0f);
ESP_LOGCONFIG(TAG, " Voltage Divider: %.1f", this->voltage_divider_);
LOG_UPDATE_INTERVAL(this)

View File

@ -5,6 +5,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/pulse_counter/pulse_counter_sensor.h"
#include <cinttypes>
namespace esphome {
namespace hlw8012 {

View File

@ -28,7 +28,7 @@ void HX711Sensor::update() {
uint32_t result;
if (this->read_sensor_(&result)) {
int32_t value = static_cast<int32_t>(result);
ESP_LOGD(TAG, "'%s': Got value %d", this->name_.c_str(), value);
ESP_LOGD(TAG, "'%s': Got value %" PRId32, this->name_.c_str(), value);
this->publish_state(value);
}
}

View File

@ -4,6 +4,8 @@
#include "esphome/core/hal.h"
#include "esphome/components/sensor/sensor.h"
#include <cinttypes>
namespace esphome {
namespace hx711 {

View File

@ -17,7 +17,7 @@ void HYT271Component::dump_config() {
LOG_SENSOR(" ", "Humidity", this->humidity_);
}
void HYT271Component::update() {
uint8_t raw_data[4];
uint8_t raw_data[4] = {0, 0, 0, 0};
if (this->write(&raw_data[0], 0) != i2c::ERROR_OK) {
this->status_set_warning();

View File

@ -180,7 +180,7 @@ void ILI9XXXDisplay::display_() {
ESP_LOGV(TAG,
"Start display(xlow:%d, ylow:%d, xhigh:%d, yhigh:%d, width:%d, "
"heigth:%d, start_pos:%d)",
"heigth:%d, start_pos:%" PRId32 ")",
this->x_low_, this->y_low_, this->x_high_, this->y_high_, w, h, start_pos);
this->start_data_();

View File

@ -1,6 +1,8 @@
#pragma once
#include "esphome/core/helpers.h"
#include <cinttypes>
namespace esphome {
namespace ili9xxx {

View File

@ -122,7 +122,7 @@ void INA219Component::setup() {
this->calibration_lsb_ = lsb;
auto calibration = uint32_t(0.04096f / (0.000001 * lsb * this->shunt_resistance_ohm_));
ESP_LOGV(TAG, " Using LSB=%u calibration=%u", lsb, calibration);
ESP_LOGV(TAG, " Using LSB=%" PRIu32 " calibration=%" PRIu32, lsb, calibration);
if (!this->write_byte_16(INA219_REGISTER_CALIBRATION, calibration)) {
this->mark_failed();
return;

View File

@ -4,6 +4,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/i2c/i2c.h"
#include <cinttypes>
namespace esphome {
namespace ina219 {

View File

@ -47,7 +47,7 @@ void MAX31855Sensor::read_data_() {
if (mem != 0xFFFFFFFF) {
this->status_clear_error();
} else {
ESP_LOGE(TAG, "No data received from MAX31855 (0x%08X). Check wiring!", mem);
ESP_LOGE(TAG, "No data received from MAX31855 (0x%08" PRIX32 "). Check wiring!", mem);
this->publish_state(NAN);
if (this->temperature_reference_) {
this->temperature_reference_->publish_state(NAN);
@ -69,25 +69,25 @@ void MAX31855Sensor::read_data_() {
// Check thermocouple faults
if (mem & 0x00000001) {
ESP_LOGW(TAG, "Thermocouple open circuit (not connected) fault from MAX31855 (0x%08X)", mem);
ESP_LOGW(TAG, "Thermocouple open circuit (not connected) fault from MAX31855 (0x%08" PRIX32 ")", mem);
this->publish_state(NAN);
this->status_set_warning();
return;
}
if (mem & 0x00000002) {
ESP_LOGW(TAG, "Thermocouple short circuit to ground fault from MAX31855 (0x%08X)", mem);
ESP_LOGW(TAG, "Thermocouple short circuit to ground fault from MAX31855 (0x%08" PRIX32 ")", mem);
this->publish_state(NAN);
this->status_set_warning();
return;
}
if (mem & 0x00000004) {
ESP_LOGW(TAG, "Thermocouple short circuit to VCC fault from MAX31855 (0x%08X)", mem);
ESP_LOGW(TAG, "Thermocouple short circuit to VCC fault from MAX31855 (0x%08" PRIX32 ")", mem);
this->publish_state(NAN);
this->status_set_warning();
return;
}
if (mem & 0x00010000) {
ESP_LOGW(TAG, "Got faulty reading from MAX31855 (0x%08X)", mem);
ESP_LOGW(TAG, "Got faulty reading from MAX31855 (0x%08" PRIX32 ")", mem);
this->publish_state(NAN);
this->status_set_warning();
return;

View File

@ -4,6 +4,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/spi/spi.h"
#include <cinttypes>
namespace esphome {
namespace max31855 {

View File

@ -188,7 +188,7 @@ uint32_t MAX31856Sensor::read_register24_(uint8_t reg) {
ESP_LOGVV(TAG, "read_byte lsb=0x%02X", lsb);
this->disable();
const uint32_t value((msb << 16) | (mid << 8) | lsb);
ESP_LOGV(TAG, "read_register_24_ reg=0x%02X: value=0x%06X", reg, value);
ESP_LOGV(TAG, "read_register_24_ reg=0x%02X: value=0x%06" PRIX32, reg, value);
return value;
}

View File

@ -4,6 +4,8 @@
#include "esphome/components/spi/spi.h"
#include "esphome/core/component.h"
#include <cinttypes>
namespace esphome {
namespace max31856 {

View File

@ -45,8 +45,8 @@ void MitsubishiClimate::transmit_state() {
remote_state[7] = (uint8_t) roundf(clamp<float>(this->target_temperature, MITSUBISHI_TEMP_MIN, MITSUBISHI_TEMP_MAX) -
MITSUBISHI_TEMP_MIN);
ESP_LOGV(TAG, "Sending Mitsubishi target temp: %.1f state: %02X mode: %02X temp: %02X", this->target_temperature,
remote_state[5], remote_state[6], remote_state[7]);
ESP_LOGV(TAG, "Sending Mitsubishi target temp: %.1f state: %02" PRIX32 " mode: %02" PRIX32 " temp: %02" PRIX32,
this->target_temperature, remote_state[5], remote_state[6], remote_state[7]);
// Checksum
for (int i = 0; i < 17; i++) {

View File

@ -2,6 +2,8 @@
#include "esphome/components/climate_ir/climate_ir.h"
#include <cinttypes>
namespace esphome {
namespace mitsubishi {

View File

@ -128,7 +128,7 @@ async def to_code(config):
use_state_callback = True
for conf in config.get(CONF_ON_ERROR, []):
trigger = cg.new_Pvariable(conf[CONF_TRIGGER_ID], var)
await automation.build_automation(trigger, [(int, "x")], conf)
await automation.build_automation(trigger, [(cg.uint8, "x")], conf)
use_state_callback = True
if use_state_callback:
cg.add_define("USE_OTA_STATE_CALLBACK")

View File

@ -54,7 +54,7 @@ class OTAEndTrigger : public Trigger<> {
}
};
class OTAErrorTrigger : public Trigger<int> {
class OTAErrorTrigger : public Trigger<uint8_t> {
public:
explicit OTAErrorTrigger(OTAComponent *parent) {
parent->add_on_state_callback([this, parent](OTAState state, float progress, uint8_t error) {

View File

@ -16,7 +16,7 @@ void PowerSupply::setup() {
void PowerSupply::dump_config() {
ESP_LOGCONFIG(TAG, "Power Supply:");
LOG_PIN(" Pin: ", this->pin_);
ESP_LOGCONFIG(TAG, " Time to enable: %u ms", this->enable_time_);
ESP_LOGCONFIG(TAG, " Time to enable: %" PRIu32 " ms", this->enable_time_);
ESP_LOGCONFIG(TAG, " Keep on time: %.1f s", this->keep_on_time_ / 1000.0f);
}

View File

@ -3,6 +3,8 @@
#include "esphome/core/component.h"
#include "esphome/core/hal.h"
#include <cinttypes>
namespace esphome {
namespace power_supply {

View File

@ -104,7 +104,7 @@ bool HwPulseCounterStorage::pulse_counter_setup(InternalGPIOPin *pin) {
if (this->filter_us != 0) {
uint16_t filter_val = std::min(static_cast<unsigned int>(this->filter_us * 80u), 1023u);
ESP_LOGCONFIG(TAG, " Filter Value: %uus (val=%u)", this->filter_us, filter_val);
ESP_LOGCONFIG(TAG, " Filter Value: %" PRIu32 "us (val=%u)", this->filter_us, filter_val);
error = pcnt_set_filter_value(this->pcnt_unit, filter_val);
if (error != ESP_OK) {
ESP_LOGE(TAG, "Setting filter value failed: %s", esp_err_to_name(error));
@ -161,7 +161,7 @@ void PulseCounterSensor::dump_config() {
LOG_PIN(" Pin: ", this->pin_);
ESP_LOGCONFIG(TAG, " Rising Edge: %s", EDGE_MODE_TO_STRING[this->storage_.rising_edge_mode]);
ESP_LOGCONFIG(TAG, " Falling Edge: %s", EDGE_MODE_TO_STRING[this->storage_.falling_edge_mode]);
ESP_LOGCONFIG(TAG, " Filtering pulses shorter than %u µs", this->storage_.filter_us);
ESP_LOGCONFIG(TAG, " Filtering pulses shorter than %" PRIu32 " µs", this->storage_.filter_us);
LOG_UPDATE_INTERVAL(this);
}
@ -177,7 +177,7 @@ void PulseCounterSensor::update() {
if (this->total_sensor_ != nullptr) {
current_total_ += raw;
ESP_LOGD(TAG, "'%s': Total : %i pulses", this->get_name().c_str(), current_total_);
ESP_LOGD(TAG, "'%s': Total : %" PRIu32 " pulses", this->get_name().c_str(), current_total_);
this->total_sensor_->publish_state(current_total_);
}
this->last_time_ = now;

View File

@ -4,6 +4,8 @@
#include "esphome/core/hal.h"
#include "esphome/components/sensor/sensor.h"
#include <cinttypes>
#if defined(USE_ESP32) && !defined(USE_ESP32_VARIANT_ESP32C3)
#include <driver/pcnt.h>
#define HAS_PCNT

View File

@ -61,12 +61,13 @@ void PulseMeterSensor::loop() {
const uint32_t time_since_valid_edge_us = now - this->last_processed_edge_us_;
switch (this->meter_state_) {
// Running and initial states can timeout
// Running and initial states can timeout
case MeterState::INITIAL:
case MeterState::RUNNING: {
if (time_since_valid_edge_us > this->timeout_us_) {
this->meter_state_ = MeterState::TIMED_OUT;
ESP_LOGD(TAG, "No pulse detected for %us, assuming 0 pulses/min", time_since_valid_edge_us / 1000000);
ESP_LOGD(TAG, "No pulse detected for %" PRIu32 "s, assuming 0 pulses/min",
time_since_valid_edge_us / 1000000);
this->publish_state(0.0f);
}
} break;
@ -82,11 +83,12 @@ void PulseMeterSensor::dump_config() {
LOG_SENSOR("", "Pulse Meter", this);
LOG_PIN(" Pin: ", this->pin_);
if (this->filter_mode_ == FILTER_EDGE) {
ESP_LOGCONFIG(TAG, " Filtering rising edges less than %u µs apart", this->filter_us_);
ESP_LOGCONFIG(TAG, " Filtering rising edges less than %" PRIu32 " µs apart", this->filter_us_);
} else {
ESP_LOGCONFIG(TAG, " Filtering pulses shorter than %u µs", this->filter_us_);
ESP_LOGCONFIG(TAG, " Filtering pulses shorter than %" PRIu32 " µs", this->filter_us_);
}
ESP_LOGCONFIG(TAG, " Assuming 0 pulses/min after not receiving a pulse for %us", this->timeout_us_ / 1000000);
ESP_LOGCONFIG(TAG, " Assuming 0 pulses/min after not receiving a pulse for %" PRIu32 "s",
this->timeout_us_ / 1000000);
}
void IRAM_ATTR PulseMeterSensor::edge_intr(PulseMeterSensor *sensor) {

View File

@ -5,6 +5,8 @@
#include "esphome/core/hal.h"
#include "esphome/core/helpers.h"
#include <cinttypes>
namespace esphome {
namespace pulse_meter {

View File

@ -14,7 +14,7 @@ void PVVXDisplay::dump_config() {
ESP_LOGCONFIG(TAG, " Characteristic UUID : %s", this->char_uuid_.to_string().c_str());
ESP_LOGCONFIG(TAG, " Auto clear : %s", YESNO(this->auto_clear_enabled_));
ESP_LOGCONFIG(TAG, " Set time on connection: %s", YESNO(this->time_ != nullptr));
ESP_LOGCONFIG(TAG, " Disconnect delay : %dms", this->disconnect_delay_ms_);
ESP_LOGCONFIG(TAG, " Disconnect delay : %" PRIu32 "ms", this->disconnect_delay_ms_);
LOG_UPDATE_INTERVAL(this);
}
@ -139,7 +139,11 @@ void PVVXDisplay::sync_time_() {
}
time.recalc_timestamp_utc(true); // calculate timestamp of local time
uint8_t blk[5] = {};
#if ESP_IDF_VERSION_MAJOR >= 5
ESP_LOGD(TAG, "[%s] Sync time with timestamp %" PRIu64 ".", this->parent_->address_str().c_str(), time.timestamp);
#else
ESP_LOGD(TAG, "[%s] Sync time with timestamp %lu.", this->parent_->address_str().c_str(), time.timestamp);
#endif
blk[0] = 0x23;
blk[1] = time.timestamp & 0xff;
blk[2] = (time.timestamp >> 8) & 0xff;

View File

@ -4,6 +4,8 @@
#include "esphome/core/defines.h"
#include "esphome/components/ble_client/ble_client.h"
#include <cinttypes>
#ifdef USE_ESP32
#include <esp_gattc_api.h>
#ifdef USE_TIME

View File

@ -57,7 +57,7 @@ void rdm6300::RDM6300Component::loop() {
trig->process(result);
if (report) {
ESP_LOGD(TAG, "Found new tag with ID %u", result);
ESP_LOGD(TAG, "Found new tag with ID %" PRIu32, result);
}
}
}

View File

@ -5,6 +5,7 @@
#include "esphome/components/binary_sensor/binary_sensor.h"
#include "esphome/components/uart/uart.h"
#include <cinttypes>
#include <vector>
namespace esphome {

View File

@ -372,19 +372,14 @@ def coolix_binary_sensor(var, config):
if isinstance(config, dict):
cg.add(
var.set_data(
cg.StructInitializer(
CoolixData,
("first", config[CONF_FIRST]),
("second", config[CONF_SECOND]),
cg.ArrayInitializer(
config[CONF_FIRST],
config[CONF_SECOND],
)
)
)
else:
cg.add(
var.set_data(
cg.StructInitializer(CoolixData, ("first", 0), ("second", config))
)
)
cg.add(var.set_data(cg.ArrayInitializer(0, config)))
@register_action("coolix", CoolixAction, COOLIX_BASE_SCHEMA)

View File

@ -101,11 +101,11 @@ optional<CoolixData> CoolixProtocol::decode(RemoteReceiveData data) {
void CoolixProtocol::dump(const CoolixData &data) {
if (data.is_strict()) {
ESP_LOGI(TAG, "Received Coolix: 0x%06X", data.first);
ESP_LOGI(TAG, "Received Coolix: 0x%06" PRIX32, data.first);
} else if (data.has_second()) {
ESP_LOGI(TAG, "Received unstrict Coolix: [0x%06X, 0x%06X]", data.first, data.second);
ESP_LOGI(TAG, "Received unstrict Coolix: [0x%06" PRIX32 ", 0x%06" PRIX32 "]", data.first, data.second);
} else {
ESP_LOGI(TAG, "Received unstrict Coolix: [0x%06X]", data.first);
ESP_LOGI(TAG, "Received unstrict Coolix: [0x%06" PRIX32 "]", data.first);
}
}

View File

@ -4,6 +4,8 @@
#include "esphome/core/helpers.h"
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -114,7 +114,7 @@ void DraytonProtocol::encode(RemoteTransmitData *dst, const DraytonData &data) {
out_data <<= NBITS_CHANNEL;
out_data |= data.channel;
ESP_LOGV(TAG, "Send Drayton: out_data %08x", out_data);
ESP_LOGV(TAG, "Send Drayton: out_data %08" PRIx32, out_data);
for (uint32_t mask = 1UL << (NBITS - 1); mask != 0; mask >>= 1) {
if (out_data & mask) {
@ -169,7 +169,7 @@ optional<DraytonData> DraytonProtocol::decode(RemoteReceiveData src) {
(src.expect_space(BIT_TIME_US) || src.peek_space(2 * BIT_TIME_US))) {
out_data |= 1 << bit;
} else {
ESP_LOGV(TAG, "Decode Drayton: Fail 1, - %d", src.get_index());
ESP_LOGV(TAG, "Decode Drayton: Fail 1, - %" PRIu32, src.get_index());
return {};
}
@ -194,7 +194,7 @@ optional<DraytonData> DraytonProtocol::decode(RemoteReceiveData src) {
} else if (src.expect_mark(BIT_TIME_US) || src.expect_mark(2 * BIT_TIME_US)) {
out_data |= 1;
}
ESP_LOGV(TAG, "Decode Drayton: Data, %2d %08x", bit, out_data);
ESP_LOGV(TAG, "Decode Drayton: Data, %2d %08" PRIx32, bit, out_data);
out.channel = (uint8_t) (out_data & 0x1F);
out_data >>= NBITS_CHANNEL;

View File

@ -3,6 +3,8 @@
#include "esphome/core/component.h"
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -46,7 +46,7 @@ optional<JVCData> JVCProtocol::decode(RemoteReceiveData src) {
}
return out;
}
void JVCProtocol::dump(const JVCData &data) { ESP_LOGI(TAG, "Received JVC: data=0x%04X", data.data); }
void JVCProtocol::dump(const JVCData &data) { ESP_LOGI(TAG, "Received JVC: data=0x%04" PRIX32, data.data); }
} // namespace remote_base
} // namespace esphome

View File

@ -2,6 +2,8 @@
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -51,7 +51,7 @@ optional<LGData> LGProtocol::decode(RemoteReceiveData src) {
return out;
}
void LGProtocol::dump(const LGData &data) {
ESP_LOGI(TAG, "Received LG: data=0x%08X, nbits=%d", data.data, data.nbits);
ESP_LOGI(TAG, "Received LG: data=0x%08" PRIX32 ", nbits=%d", data.data, data.nbits);
}
} // namespace remote_base

View File

@ -3,6 +3,8 @@
#include "esphome/core/component.h"
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -76,7 +76,7 @@ optional<MagiQuestData> MagiQuestProtocol::decode(RemoteReceiveData src) {
return data;
}
void MagiQuestProtocol::dump(const MagiQuestData &data) {
ESP_LOGI(TAG, "Received MagiQuest: wand_id=0x%08X, magnitude=0x%04X", data.wand_id, data.magnitude);
ESP_LOGI(TAG, "Received MagiQuest: wand_id=0x%08" PRIX32 ", magnitude=0x%04X", data.wand_id, data.magnitude);
}
} // namespace remote_base

View File

@ -2,6 +2,8 @@
#include "remote_base.h"
#include <cinttypes>
/* Based on protocol analysis from
* https://arduino-irremote.github.io/Arduino-IRremote/ir__MagiQuest_8cpp_source.html
*/

View File

@ -232,7 +232,7 @@ optional<NexaData> NexaProtocol::decode(RemoteReceiveData src) {
}
void NexaProtocol::dump(const NexaData &data) {
ESP_LOGI(TAG, "Received NEXA: device=0x%04X group=%d state=%d channel=%d level=%d", data.device, data.group,
ESP_LOGI(TAG, "Received NEXA: device=0x%04" PRIX32 " group=%d state=%d channel=%d level=%d", data.device, data.group,
data.state, data.channel, data.level);
}

View File

@ -2,6 +2,8 @@
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -67,7 +67,7 @@ optional<PanasonicData> PanasonicProtocol::decode(RemoteReceiveData src) {
return out;
}
void PanasonicProtocol::dump(const PanasonicData &data) {
ESP_LOGI(TAG, "Received Panasonic: address=0x%04X, command=0x%08X", data.address, data.command);
ESP_LOGI(TAG, "Received Panasonic: address=0x%04X, command=0x%08" PRIX32, data.address, data.command);
}
} // namespace remote_base

View File

@ -3,6 +3,8 @@
#include "esphome/core/component.h"
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -17,9 +17,9 @@ bool RawDumper::dump(RemoteReceiveData src) {
int written;
if (i + 1 < src.size() - 1) {
written = snprintf(buffer + buffer_offset, remaining_length, "%d, ", value);
written = snprintf(buffer + buffer_offset, remaining_length, "%" PRId32 ", ", value);
} else {
written = snprintf(buffer + buffer_offset, remaining_length, "%d", value);
written = snprintf(buffer + buffer_offset, remaining_length, "%" PRId32, value);
}
if (written < 0 || written >= int(remaining_length)) {
@ -29,9 +29,9 @@ bool RawDumper::dump(RemoteReceiveData src) {
buffer_offset = 0;
written = sprintf(buffer, " ");
if (i + 1 < src.size()) {
written += sprintf(buffer + written, "%d, ", value);
written += sprintf(buffer + written, "%" PRId32 ", ", value);
} else {
written += sprintf(buffer + written, "%d", value);
written += sprintf(buffer + written, "%" PRId32, value);
}
}

View File

@ -3,6 +3,7 @@
#include "esphome/core/component.h"
#include "remote_base.h"
#include <cinttypes>
#include <vector>
namespace esphome {

View File

@ -96,7 +96,7 @@ optional<Samsung36Data> Samsung36Protocol::decode(RemoteReceiveData src) {
return out;
}
void Samsung36Protocol::dump(const Samsung36Data &data) {
ESP_LOGI(TAG, "Received Samsung36: address=0x%04X, command=0x%08X", data.address, data.command);
ESP_LOGI(TAG, "Received Samsung36: address=0x%04X, command=0x%08" PRIX32, data.address, data.command);
}
} // namespace remote_base

View File

@ -3,6 +3,8 @@
#include "esphome/core/component.h"
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -62,7 +62,7 @@ optional<SonyData> SonyProtocol::decode(RemoteReceiveData src) {
return out;
}
void SonyProtocol::dump(const SonyData &data) {
ESP_LOGI(TAG, "Received Sony: data=0x%08X, nbits=%d", data.data, data.nbits);
ESP_LOGI(TAG, "Received Sony: data=0x%08" PRIX32 ", nbits=%d", data.data, data.nbits);
}
} // namespace remote_base

View File

@ -3,6 +3,8 @@
#include "esphome/core/component.h"
#include "remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_base {

View File

@ -3,6 +3,8 @@
#include "esphome/core/component.h"
#include "esphome/components/remote_base/remote_base.h"
#include <cinttypes>
namespace esphome {
namespace remote_receiver {

View File

@ -62,7 +62,7 @@ void RemoteReceiverComponent::dump_config() {
ESP_LOGCONFIG(TAG, " Clock divider: %u", this->clock_divider_);
ESP_LOGCONFIG(TAG, " Tolerance: %u%%", this->tolerance_);
ESP_LOGCONFIG(TAG, " Filter out pulses shorter than: %u us", this->filter_us_);
ESP_LOGCONFIG(TAG, " Signal is done after %u us of no changes", this->idle_us_);
ESP_LOGCONFIG(TAG, " Signal is done after %" PRIu32 " us of no changes", this->idle_us_);
if (this->is_failed()) {
ESP_LOGE(TAG, "Configuring RMT driver failed: %s", esp_err_to_name(this->error_code_));
}

View File

@ -255,7 +255,7 @@ void SGP30Component::dump_config() {
} else {
ESP_LOGCONFIG(TAG, " Baseline: No baseline configured");
}
ESP_LOGCONFIG(TAG, " Warm up time: %us", this->required_warm_up_time_);
ESP_LOGCONFIG(TAG, " Warm up time: %" PRIu32 "s", this->required_warm_up_time_);
}
LOG_UPDATE_INTERVAL(this);
LOG_SENSOR(" ", "eCO2 sensor", this->eco2_sensor_);

View File

@ -4,6 +4,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/sensirion_common/i2c_sensirion.h"
#include "esphome/core/preferences.h"
#include <cinttypes>
#include <cmath>
namespace esphome {

View File

@ -27,7 +27,7 @@ void SHT3XDComponent::setup() {
return;
}
uint32_t serial_number = (uint32_t(raw_serial_number[0]) << 16) | uint32_t(raw_serial_number[1]);
ESP_LOGV(TAG, " Serial Number: 0x%08X", serial_number);
ESP_LOGV(TAG, " Serial Number: 0x%08" PRIX32, serial_number);
}
void SHT3XDComponent::dump_config() {
ESP_LOGCONFIG(TAG, "SHT3xD:");

View File

@ -4,6 +4,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/sensirion_common/i2c_sensirion.h"
#include <cinttypes>
namespace esphome {
namespace sht3xd {

View File

@ -20,7 +20,7 @@ void SHT4XComponent::setup() {
if (this->duty_cycle_ > 0.0) {
uint32_t heater_interval = (uint32_t) (this->heater_time_ / this->duty_cycle_);
ESP_LOGD(TAG, "Heater interval: %i", heater_interval);
ESP_LOGD(TAG, "Heater interval: %" PRIu32, heater_interval);
if (this->heater_power_ == SHT4X_HEATERPOWER_HIGH) {
if (this->heater_time_ == SHT4X_HEATERTIME_LONG) {

View File

@ -4,6 +4,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/sensirion_common/i2c_sensirion.h"
#include <cinttypes>
namespace esphome {
namespace sht4x {

View File

@ -30,7 +30,7 @@ void STS3XComponent::setup() {
return;
}
uint32_t serial_number = (uint32_t(raw_serial_number[0]) << 16);
ESP_LOGV(TAG, " Serial Number: 0x%08X", serial_number);
ESP_LOGV(TAG, " Serial Number: 0x%08" PRIX32, serial_number);
}
void STS3XComponent::dump_config() {
ESP_LOGCONFIG(TAG, "STS3x:");

View File

@ -4,6 +4,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/sensirion_common/i2c_sensirion.h"
#include <cinttypes>
namespace esphome {
namespace sts3x {

View File

@ -26,14 +26,14 @@ void TemplateAlarmControlPanel::dump_config() {
ESP_LOGCONFIG(TAG, " Number of Codes: %u", this->codes_.size());
if (!this->codes_.empty())
ESP_LOGCONFIG(TAG, " Requires Code To Arm: %s", YESNO(this->requires_code_to_arm_));
ESP_LOGCONFIG(TAG, " Arming Away Time: %us", (this->arming_away_time_ / 1000));
ESP_LOGCONFIG(TAG, " Arming Away Time: %" PRIu32 "s", (this->arming_away_time_ / 1000));
if (this->arming_home_time_ != 0)
ESP_LOGCONFIG(TAG, " Arming Home Time: %us", (this->arming_home_time_ / 1000));
ESP_LOGCONFIG(TAG, " Arming Home Time: %" PRIu32 "s", (this->arming_home_time_ / 1000));
if (this->arming_night_time_ != 0)
ESP_LOGCONFIG(TAG, " Arming Night Time: %us", (this->arming_night_time_ / 1000));
ESP_LOGCONFIG(TAG, " Pending Time: %us", (this->pending_time_ / 1000));
ESP_LOGCONFIG(TAG, " Trigger Time: %us", (this->trigger_time_ / 1000));
ESP_LOGCONFIG(TAG, " Supported Features: %u", this->get_supported_features());
ESP_LOGCONFIG(TAG, " Arming Night Time: %" PRIu32 "s", (this->arming_night_time_ / 1000));
ESP_LOGCONFIG(TAG, " Pending Time: %" PRIu32 "s", (this->pending_time_ / 1000));
ESP_LOGCONFIG(TAG, " Trigger Time: %" PRIu32 "s", (this->trigger_time_ / 1000));
ESP_LOGCONFIG(TAG, " Supported Features: %" PRIu32, this->get_supported_features());
#ifdef USE_BINARY_SENSOR
for (auto sensor_pair : this->sensor_map_) {
ESP_LOGCONFIG(TAG, " Binary Sesnsor:");

View File

@ -1,5 +1,6 @@
#pragma once
#include <cinttypes>
#include <map>
#include "esphome/core/automation.h"

View File

@ -142,8 +142,8 @@ void TSL2591Component::process_update_() {
uint16_t full = this->get_illuminance(TSL2591_SENSOR_CHANNEL_FULL_SPECTRUM, combined);
float lux = this->get_calculated_lux(full, infrared);
uint16_t actual_gain = this->get_actual_gain();
ESP_LOGD(TAG, "Got illuminance: combined 0x%X, full %d, IR %d, vis %d. Calc lux: %f. Actual gain: %d.", combined,
full, infrared, visible, lux, actual_gain);
ESP_LOGD(TAG, "Got illuminance: combined 0x%" PRIX32 ", full %d, IR %d, vis %d. Calc lux: %f. Actual gain: %d.",
combined, full, infrared, visible, lux, actual_gain);
if (this->full_spectrum_sensor_ != nullptr) {
this->full_spectrum_sensor_->publish_state(full);
}

View File

@ -4,6 +4,8 @@
#include "esphome/components/sensor/sensor.h"
#include "esphome/components/i2c/i2c.h"
#include <cinttypes>
namespace esphome {
namespace tsl2591 {

View File

@ -53,7 +53,7 @@ void UARTSwitch::write_state(bool state) {
void UARTSwitch::dump_config() {
LOG_SWITCH("", "UART Switch", this);
if (this->send_every_) {
ESP_LOGCONFIG(TAG, " Send Every: %u", this->send_every_);
ESP_LOGCONFIG(TAG, " Send Every: %" PRIu32, this->send_every_);
}
}

View File

@ -4,6 +4,7 @@
#include "esphome/components/uart/uart.h"
#include "esphome/components/switch/switch.h"
#include <cinttypes>
#include <vector>
namespace esphome {

View File

@ -30,7 +30,7 @@ void UltrasonicSensorComponent::update() {
;
const uint32_t pulse_end = micros();
ESP_LOGV(TAG, "Echo took %uµs", pulse_end - pulse_start);
ESP_LOGV(TAG, "Echo took %" PRIu32 "µs", pulse_end - pulse_start);
if (pulse_end - start >= timeout_us_) {
ESP_LOGD(TAG, "'%s' - Distance measurement timed out!", this->name_.c_str());
@ -45,8 +45,8 @@ void UltrasonicSensorComponent::dump_config() {
LOG_SENSOR("", "Ultrasonic Sensor", this);
LOG_PIN(" Echo Pin: ", this->echo_pin_);
LOG_PIN(" Trigger Pin: ", this->trigger_pin_);
ESP_LOGCONFIG(TAG, " Pulse time: %u µs", this->pulse_time_us_);
ESP_LOGCONFIG(TAG, " Timeout: %u µs", this->timeout_us_);
ESP_LOGCONFIG(TAG, " Pulse time: %" PRIu32 " µs", this->pulse_time_us_);
ESP_LOGCONFIG(TAG, " Timeout: %" PRIu32 " µs", this->timeout_us_);
LOG_UPDATE_INTERVAL(this);
}
float UltrasonicSensorComponent::us_to_m(uint32_t us) {

View File

@ -4,6 +4,8 @@
#include "esphome/core/gpio.h"
#include "esphome/components/sensor/sensor.h"
#include <cinttypes>
namespace esphome {
namespace ultrasonic {

View File

@ -118,7 +118,7 @@ bool Whynter::on_receive(remote_base::RemoteReceiveData data) {
}
}
ESP_LOGD(TAG, "Decoded 0x%02X", remote_state);
ESP_LOGD(TAG, "Decoded 0x%02" PRIX32, remote_state);
if ((remote_state & COMMAND_MASK) != COMMAND_CODE)
return false;
if ((remote_state & POWER_MASK) != POWER_MASK) {
@ -156,7 +156,7 @@ bool Whynter::on_receive(remote_base::RemoteReceiveData data) {
}
void Whynter::transmit_(uint32_t value) {
ESP_LOGD(TAG, "Sending whynter code: 0x%02X", value);
ESP_LOGD(TAG, "Sending Whynter code: 0x%02" PRIX32, value);
auto transmit = this->transmitter_->transmit();
auto *data = transmit.get_data();

View File

@ -2,6 +2,8 @@
#include "esphome/components/climate_ir/climate_ir.h"
#include <cinttypes>
namespace esphome {
namespace whynter {