ESPHome 2025.7.4
|
#include <component.h>
Public Member Functions | |
virtual void | setup () |
Where the component's initialization should happen. | |
virtual void | loop () |
This method will be called repeatedly. | |
virtual void | dump_config () |
virtual float | get_setup_priority () const |
priority of setup(). | |
float | get_actual_setup_priority () const |
void | set_setup_priority (float priority) |
virtual float | get_loop_priority () const |
priority of loop(). | |
void | call () |
virtual void | on_shutdown () |
virtual void | on_safe_shutdown () |
virtual bool | teardown () |
Called during teardown to allow component to gracefully finish operations. | |
virtual void | on_powerdown () |
Called after teardown is complete to power down hardware. | |
uint8_t | get_component_state () const |
void | reset_to_construction_state () |
Reset this component back to the construction state to allow setup to run again. | |
bool | is_in_loop_state () const |
Check if this component has completed setup and is in the loop state. | |
virtual void | mark_failed () |
Mark this component as failed. | |
void | mark_failed (const char *message) |
void | disable_loop () |
Disable this component's loop. | |
void | enable_loop () |
Enable this component's loop. | |
void | enable_loop_soon_any_context () |
Thread and ISR-safe version of enable_loop() that can be called from any context. | |
bool | is_failed () const |
bool | is_ready () const |
virtual bool | can_proceed () |
bool | status_has_warning () const |
bool | status_has_error () const |
void | status_set_warning (const char *message="unspecified") |
void | status_set_error (const char *message="unspecified") |
void | status_clear_warning () |
void | status_clear_error () |
void | status_momentary_warning (const std::string &name, uint32_t length=5000) |
void | status_momentary_error (const std::string &name, uint32_t length=5000) |
bool | has_overridden_loop () const |
void | set_component_source (const char *source) |
Set where this component was loaded from for some debug messages. | |
const char * | get_component_source () const |
Get the integration where this component was declared as a string. | |
bool | should_warn_of_blocking (uint32_t blocking_time) |
Protected Member Functions | |
virtual void | call_loop () |
virtual void | call_setup () |
virtual void | call_dump_config () |
void | set_interval (const std::string &name, uint32_t interval, std::function< void()> &&f) |
Set an interval function with a unique name. | |
void | set_interval (const char *name, uint32_t interval, std::function< void()> &&f) |
Set an interval function with a const char* name. | |
void | set_interval (uint32_t interval, std::function< void()> &&f) |
bool | cancel_interval (const std::string &name) |
Cancel an interval function. | |
bool | cancel_interval (const char *name) |
void | set_retry (const std::string &name, uint32_t initial_wait_time, uint8_t max_attempts, std::function< RetryResult(uint8_t)> &&f, float backoff_increase_factor=1.0f) |
Set an retry function with a unique name. | |
void | set_retry (uint32_t initial_wait_time, uint8_t max_attempts, std::function< RetryResult(uint8_t)> &&f, float backoff_increase_factor=1.0f) |
bool | cancel_retry (const std::string &name) |
Cancel a retry function. | |
void | set_timeout (const std::string &name, uint32_t timeout, std::function< void()> &&f) |
Set a timeout function with a unique name. | |
void | set_timeout (const char *name, uint32_t timeout, std::function< void()> &&f) |
Set a timeout function with a const char* name. | |
void | set_timeout (uint32_t timeout, std::function< void()> &&f) |
bool | cancel_timeout (const std::string &name) |
Cancel a timeout function. | |
bool | cancel_timeout (const char *name) |
void | defer (const std::string &name, std::function< void()> &&f) |
Defer a callback to the next loop() call. | |
void | defer (const char *name, std::function< void()> &&f) |
Defer a callback to the next loop() call with a const char* name. | |
void | defer (std::function< void()> &&f) |
Defer a callback to the next loop() call. | |
bool | cancel_defer (const std::string &name) |
Cancel a defer callback using the specified name, name must not be empty. | |
Protected Attributes | |
const char * | component_source_ {nullptr} |
uint16_t | warn_if_blocking_over_ {WARN_IF_BLOCKING_OVER_MS} |
Warn if blocked for this many ms (max 65.5s) | |
uint8_t | component_state_ {0x00} |
State of this component - each bit has a purpose: Bits 0-1: Component state (0x00=CONSTRUCTION, 0x01=SETUP, 0x02=LOOP, 0x03=FAILED) Bit 2: STATUS_LED_WARNING Bit 3: STATUS_LED_ERROR Bits 4-7: Unused - reserved for future expansion (50% of the bits are free) | |
volatile bool | pending_enable_loop_ {false} |
ISR-safe flag for enable_loop_soon_any_context. | |
Definition at line 71 of file component.h.
void esphome::Component::call | ( | ) |
Definition at line 146 of file component.cpp.
|
protectedvirtual |
Reimplemented in esphome::mqtt::MQTTComponent.
Definition at line 128 of file component.cpp.
|
protectedvirtual |
Reimplemented in esphome::mqtt::MQTTComponent.
Definition at line 126 of file component.cpp.
|
protectedvirtual |
Reimplemented in esphome::light::AddressableLight, esphome::mqtt::MQTTComponent, esphome::PollingComponent, and esphome::touchscreen::Touchscreen.
Definition at line 127 of file component.cpp.
|
virtual |
Reimplemented in esphome::cst226::CST226Touchscreen, esphome::esp32_ble_server::BLEServer, esphome::ethernet::EthernetComponent, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::mipi_spi::MipiSpi, esphome::mqtt::MQTTClientComponent, esphome::qspi_dbi::QspiDbi, esphome::wifi::WiFiComponent, and esphome::wireguard::Wireguard.
Definition at line 270 of file component.cpp.
|
protected |
Cancel a defer callback using the specified name, name must not be empty.
Definition at line 245 of file component.cpp.
|
protected |
Definition at line 97 of file component.cpp.
|
protected |
Cancel an interval function.
name | The identifier for this interval function. |
Definition at line 93 of file component.cpp.
|
protected |
Cancel a retry function.
name | The identifier for this retry function. |
Definition at line 106 of file component.cpp.
|
protected |
Definition at line 122 of file component.cpp.
|
protected |
Cancel a timeout function.
name | The identifier for this timeout function. |
Definition at line 118 of file component.cpp.
|
protected |
Defer a callback to the next loop() call with a const char* name.
IMPORTANT: The provided name pointer must remain valid for the lifetime of the deferred task. This means the name should be:
For dynamic strings, use the std::string overload instead.
name | The name of the defer function (must have static lifetime) |
f | The callback |
Definition at line 251 of file component.cpp.
|
protected |
Defer a callback to the next loop() call.
If name is specified and a defer() object with the same name exists, the old one is first removed.
name | The name of the defer function. |
f | The callback. |
Definition at line 248 of file component.cpp.
|
protected |
Defer a callback to the next loop() call.
Definition at line 242 of file component.cpp.
void esphome::Component::disable_loop | ( | ) |
Disable this component's loop.
The loop() method will no longer be called.
This is useful for components that only need to run for a certain period of time or when inactive, saving CPU cycles.
Definition at line 201 of file component.cpp.
|
virtual |
Reimplemented in esphome::a01nyub::A01nyubComponent, esphome::a02yyuw::A02yyuwComponent, esphome::a4988::A4988, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::ac_dimmer::AcDimmer, esphome::adc128s102::ADC128S102, esphome::adc128s102::ADC128S102Sensor, esphome::adc::ADCSensor, esphome::ade7880::ADE7880, esphome::ade7953_base::ADE7953, esphome::ade7953_i2c::AdE7953I2c, esphome::ade7953_spi::AdE7953Spi, esphome::ads1115::ADS1115Component, esphome::ads1115::ADS1115Sensor, esphome::ads1118::ADS1118, esphome::ads1118::ADS1118Sensor, esphome::ags10::AGS10Component, esphome::aht10::AHT10Component, esphome::aic3204::AIC3204, esphome::airthings_wave_mini::AirthingsWaveMini, esphome::airthings_wave_plus::AirthingsWavePlus, esphome::alpha3::Alpha3, esphome::am2315c::AM2315C, esphome::am2320::AM2320Component, esphome::am43::Am43, esphome::am43::Am43Component, esphome::analog_threshold::AnalogThresholdBinarySensor, esphome::anova::Anova, esphome::apds9306::APDS9306, esphome::api::APIServer, esphome::as3935_i2c::I2CAS3935Component, esphome::as3935_spi::SPIAS3935Component, esphome::as5600::AS5600Component, esphome::as5600::AS5600Sensor, esphome::as7341::AS7341Component, esphome::at581x::AT581XComponent, esphome::atc_mithermometer::ATCMiThermometer, esphome::atm90e26::ATM90E26Component, esphome::atm90e32::ATM90E32Component, esphome::axs15231::AXS15231Touchscreen, esphome::b_parasite::BParasite, esphome::bang_bang::BangBangClimate, esphome::bedjet::BedJetClimate, esphome::bedjet::BedJetFan, esphome::bedjet::BedJetHub, esphome::bedjet::BedjetSensor, esphome::beken_spi_led_strip::BekenSPILEDStripLightOutput, esphome::bh1750::BH1750Sensor, esphome::binary::BinaryFan, esphome::binary_sensor_map::BinarySensorMap, esphome::bl0939::BL0939, esphome::bl0940::BL0940, esphome::bl0942::BL0942, esphome::ble_client::BLEBinaryOutput, esphome::ble_client::BLEClient, esphome::ble_client::BLEClientRSSISensor, esphome::ble_client::BLEClientSwitch, esphome::ble_client::BLESensor, esphome::ble_client::BLETextSensor, esphome::ble_presence::BLEPresenceDevice, esphome::ble_rssi::BLERSSISensor, esphome::ble_scanner::BLEScanner, esphome::bluetooth_proxy::BluetoothConnection, esphome::bluetooth_proxy::BluetoothProxy, esphome::bme280_base::BME280Component, esphome::bme680::BME680Component, esphome::bme680_bsec::BME680BSECComponent, esphome::bme68x_bsec2::BME68xBSEC2Component, esphome::bmi160::BMI160Component, esphome::bmp085::BMP085Component, esphome::bmp280_base::BMP280Component, esphome::bmp280_i2c::BMP280I2CComponent, esphome::bmp3xx_base::BMP3XXComponent, esphome::bmp581::BMP581Component, esphome::bp1658cj::BP1658CJ, esphome::bp5758d::BP5758D, esphome::canbus::Canbus, esphome::cap1188::CAP1188Component, esphome::captive_portal::CaptivePortal, esphome::ccs811::CCS811Component, esphome::cd74hc4067::CD74HC4067Component, esphome::cd74hc4067::CD74HC4067Sensor, esphome::ch422g::CH422GComponent, esphome::chsc6x::CHSC6XTouchscreen, esphome::climate_ir::ClimateIR, esphome::cm1106::CM1106Component, esphome::combination::KalmanCombinationComponent, esphome::combination::LinearCombinationComponent, esphome::combination::MaximumCombinationComponent, esphome::combination::MeanCombinationComponent, esphome::combination::MedianCombinationComponent, esphome::combination::MinimumCombinationComponent, esphome::combination::MostRecentCombinationComponent, esphome::combination::RangeCombinationComponent, esphome::combination::SumCombinationComponent, esphome::copy::CopyBinarySensor, esphome::copy::CopyButton, esphome::copy::CopyCover, esphome::copy::CopyFan, esphome::copy::CopyLock, esphome::copy::CopyNumber, esphome::copy::CopySelect, esphome::copy::CopySensor, esphome::copy::CopySwitch, esphome::copy::CopyText, esphome::copy::CopyTextSensor, esphome::cs5460a::CS5460AComponent, esphome::cse7761::CSE7761Component, esphome::cse7766::CSE7766Component, esphome::cst226::CST226Button, esphome::cst226::CST226Touchscreen, esphome::cst816::CST816Touchscreen, esphome::ct_clamp::CTClampSensor, esphome::current_based::CurrentBasedCover, esphome::dac7678::DAC7678Output, esphome::dallas_temp::DallasTemperatureSensor, esphome::daly_bms::DalyBmsComponent, esphome::debug::DebugComponent, esphome::deep_sleep::DeepSleepComponent, esphome::dfplayer::DFPlayer, esphome::dht12::DHT12Component, esphome::dht::DHT, esphome::dps310::DPS310Component, esphome::ds1307::DS1307Component, esphome::ds2484::DS2484OneWireBus, esphome::dsmr::Dsmr, esphome::duty_cycle::DutyCycleSensor, esphome::duty_time_sensor::DutyTimeSensor, esphome::ee895::EE895Component, esphome::ektf2232::EKTF2232Touchscreen, esphome::emc2101::Emc2101Component, esphome::emc2101::EMC2101Sensor, esphome::endstop::EndstopCover, esphome::ens160_base::ENS160Component, esphome::ens210::ENS210Component, esphome::es7210::ES7210, esphome::es7243e::ES7243E, esphome::es8156::ES8156, esphome::es8311::ES8311, esphome::esp32_ble::ESP32BLE, esphome::esp32_ble_beacon::ESP32BLEBeacon, esphome::esp32_ble_client::BLEClientBase, esphome::esp32_ble_server::BLEServer, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::esp32_camera::ESP32Camera, esphome::esp32_camera_web_server::CameraWebServer, esphome::esp32_dac::ESP32DAC, esphome::esp32_improv::ESP32ImprovComponent, esphome::esp32_rmt_led_strip::ESP32RMTLEDStripLightOutput, esphome::esp32_touch::ESP32TouchComponent, esphome::esp8266_pwm::ESP8266PWM, esphome::esp_ldo::EspLdo, esphome::ESPHomeOTAComponent, esphome::ethernet::EthernetComponent, esphome::ethernet_info::DNSAddressEthernetInfo, esphome::ethernet_info::IPAddressEthernetInfo, esphome::ethernet_info::MACAddressEthernetInfo, esphome::ezo::EZOSensor, esphome::ezo_pmp::EzoPMP, esphome::factory_reset::FactoryResetButton, esphome::factory_reset::FactoryResetSwitch, esphome::fastled_base::FastLEDLightOutput, esphome::feedback::FeedbackCover, esphome::fingerprint_grow::FingerprintGrowComponent, esphome::fs3000::FS3000Component, esphome::ft5x06::FT5x06Touchscreen, esphome::ft63x6::FT63X6Touchscreen, esphome::gcja5::GCJA5Component, esphome::gl_r01_i2c::GLR01I2CComponent, esphome::gp2y1010au0f::GP2Y1010AU0FSensor, esphome::gp8403::GP8403, esphome::gp8403::GP8403Output, esphome::gpio::GPIOBinaryOutput, esphome::gpio::GPIOBinarySensor, esphome::gpio::GPIOOneWireBus, esphome::gpio::GPIOSwitch, esphome::gps::GPS, esphome::graph::Graph, esphome::graphical_display_menu::GraphicalDisplayMenu, esphome::grove_tb6612fng::GroveMotorDriveTB6612FNG, esphome::growatt_solar::GrowattSolar, esphome::gt911::GT911Button, esphome::gt911::GT911Touchscreen, esphome::haier::HaierClimateBase, esphome::haier::HonClimate, esphome::haier::Smartair2Climate, esphome::havells_solar::HavellsSolar, esphome::hbridge::HBridgeFan, esphome::hbridge::HBridgeSwitch, esphome::hdc1080::HDC1080Component, esphome::he60r::HE60rCover, esphome::hlw8012::HLW8012Component, esphome::hm3301::HM3301Component, esphome::hmc5883l::HMC5883LComponent, esphome::homeassistant::HomeassistantBinarySensor, esphome::homeassistant::HomeassistantNumber, esphome::homeassistant::HomeassistantSensor, esphome::homeassistant::HomeassistantSwitch, esphome::homeassistant::HomeassistantTextSensor, esphome::homeassistant::HomeassistantTime, esphome::honeywell_hih_i2c::HoneywellHIComponent, esphome::honeywellabp2_i2c::HONEYWELLABP2Sensor, esphome::honeywellabp::HONEYWELLABPSensor, esphome::hrxl_maxsonar_wr::HrxlMaxsonarWrComponent, esphome::hte501::HTE501Component, esphome::http_request::HttpRequestComponent, esphome::http_request::HttpRequestIDF, esphome::http_request::OtaHttpRequestComponent, esphome::htu21d::HTU21DComponent, esphome::htu31d::HTU31DComponent, esphome::hx711::HX711Sensor, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::hyt271::HYT271Component, esphome::i2c::ArduinoI2CBus, esphome::i2c::IDFI2CBus, esphome::i2c_device::I2CDeviceComponent, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::i2s_audio::I2SAudioMicrophone, esphome::i2s_audio::I2SAudioSpeaker, esphome::iaqcore::IAQCore, esphome::ili9xxx::ILI9XXXDisplay, esphome::improv_serial::ImprovSerialComponent, esphome::ina219::INA219Component, esphome::ina226::INA226Component, esphome::ina260::INA260Component, esphome::ina2xx_base::INA2XX, esphome::ina2xx_i2c::INA2XXI2C, esphome::ina2xx_spi::INA2XXSPI, esphome::ina3221::INA3221Component, esphome::inkbird_ibsth1_mini::InkbirdIbstH1Mini, esphome::inkplate6::Inkplate6, esphome::integration::IntegrationSensor, esphome::internal_temperature::InternalTemperatureSensor, esphome::jsn_sr04t::Jsnsr04tComponent, esphome::kamstrup_kmp::KamstrupKMPComponent, esphome::key_collector::KeyCollector, esphome::kuntze::Kuntze, esphome::lc709203f::Lc709203f, esphome::lcd_gpio::GPIOLCDDisplay, esphome::lcd_menu::LCDCharacterMenuComponent, esphome::lcd_pcf8574::PCF8574LCDDisplay, esphome::ld2420::LD2420BinarySensor, esphome::ld2420::LD2420Component, esphome::ld2420::LD2420Sensor, esphome::ld2420::LD2420TextSensor, esphome::ledc::LEDCOutput, esphome::libretiny::LTComponent, esphome::libretiny_pwm::LibreTinyPWM, esphome::light::LightState, esphome::lightwaverf::LightWaveRF, esphome::lilygo_t5_47::LilygoT547Touchscreen, esphome::logger::Logger, esphome::lps22::LPS22Component, esphome::ltr390::LTR390Component, esphome::ltr501::LTRAlsPs501Component, esphome::ltr_als_ps::LTRAlsPsComponent, esphome::lvgl::LvglComponent, esphome::m5stack_8angle::M5Stack8AngleComponent, esphome::matrix_keypad::MatrixKeypad, esphome::max17043::MAX17043Component, esphome::max31855::MAX31855Sensor, esphome::max31856::MAX31856Sensor, esphome::max31865::MAX31865Sensor, esphome::max44009::MAX44009Sensor, esphome::max6675::MAX6675Sensor, esphome::max6956::MAX6956, esphome::max6956::MAX6956LedChannel, esphome::max7219::MAX7219Component, esphome::max7219digit::MAX7219Component, esphome::max9611::MAX9611Component, esphome::mcp23008::MCP23008, esphome::mcp23017::MCP23017, esphome::mcp23s08::MCP23S08, esphome::mcp23s17::MCP23S17, esphome::mcp3008::MCP3008, esphome::mcp3008::MCP3008Sensor, esphome::mcp3204::MCP3204, esphome::mcp3204::MCP3204Sensor, esphome::mcp4461::Mcp4461Component, esphome::mcp4725::MCP4725, esphome::mcp4728::MCP4728Component, esphome::mcp47a1::MCP47A1, esphome::mcp9600::MCP9600Component, esphome::mcp9808::MCP9808Sensor, esphome::mdns::MDNSComponent, esphome::mhz19::MHZ19Component, esphome::micro_wake_word::MicroWakeWord, esphome::micronova::MicroNova, esphome::micronova::MicroNovaButton, esphome::micronova::MicroNovaSwitch, esphome::midea::ac::AirConditioner, esphome::mipi_spi::MipiSpi, esphome::mixer_speaker::MixerSpeaker, esphome::mixer_speaker::SourceSpeaker, esphome::mlx90393::MLX90393Cls, esphome::mlx90614::MLX90614Component, esphome::mmc5603::MMC5603Component, esphome::mmc5983::MMC5983Component, esphome::modbus::Modbus, esphome::modbus_controller::ModbusBinaryOutput, esphome::modbus_controller::ModbusBinarySensor, esphome::modbus_controller::ModbusController, esphome::modbus_controller::ModbusFloatOutput, esphome::modbus_controller::ModbusNumber, esphome::modbus_controller::ModbusSelect, esphome::modbus_controller::ModbusSensor, esphome::modbus_controller::ModbusSwitch, esphome::modbus_controller::ModbusTextSensor, esphome::mopeka_pro_check::MopekaProCheck, esphome::mopeka_std_check::MopekaStdCheck, esphome::mpl3115a2::MPL3115A2Component, esphome::mpr121::MPR121Component, esphome::mpu6050::MPU6050Component, esphome::mpu6886::MPU6886Component, esphome::mqtt::MQTTAlarmControlPanelComponent, esphome::mqtt::MQTTBinarySensorComponent, esphome::mqtt::MQTTButtonComponent, esphome::mqtt::MQTTClientComponent, esphome::mqtt::MQTTCoverComponent, esphome::mqtt::MQTTDateComponent, esphome::mqtt::MQTTDateTimeComponent, esphome::mqtt::MQTTEventComponent, esphome::mqtt::MQTTFanComponent, esphome::mqtt::MQTTJSONLightComponent, esphome::mqtt::MQTTLockComponent, esphome::mqtt::MQTTMessageTrigger, esphome::mqtt::MQTTNumberComponent, esphome::mqtt::MQTTSelectComponent, esphome::mqtt::MQTTSensorComponent, esphome::mqtt::MQTTSwitchComponent, esphome::mqtt::MQTTTextComponent, esphome::mqtt::MQTTTextSensor, esphome::mqtt::MQTTTimeComponent, esphome::mqtt::MQTTUpdateComponent, esphome::mqtt::MQTTValveComponent, esphome::mqtt_subscribe::MQTTSubscribeSensor, esphome::mqtt_subscribe::MQTTSubscribeTextSensor, esphome::ms5611::MS5611Component, esphome::ms8607::MS8607Component, esphome::msa3xx::MSA3xxComponent, esphome::my9231::MY9231OutputComponent, esphome::nau7802::NAU7802Sensor, esphome::nextion::Nextion, esphome::nfc::NfcTagBinarySensor, esphome::npi19::NPI19Component, esphome::ntc::NTC, esphome::opentherm::OpenthermHub, esphome::opentherm::OpenthermNumber, esphome::opentherm::OpenthermSwitch, esphome::openthread_info::ChannelOpenThreadInfo, esphome::openthread_info::Eui64OpenThreadInfo, esphome::openthread_info::ExtAddrOpenThreadInfo, esphome::openthread_info::ExtPanIdOpenThreadInfo, esphome::openthread_info::IPAddressOpenThreadInfo, esphome::openthread_info::NetworkKeyOpenThreadInfo, esphome::openthread_info::NetworkNameOpenThreadInfo, esphome::openthread_info::PanIdOpenThreadInfo, esphome::openthread_info::Rloc16OpenThreadInfo, esphome::openthread_info::RoleOpenThreadInfo, esphome::opt3001::OPT3001Sensor, esphome::output::OutputButton, esphome::output::OutputLock, esphome::output::OutputSwitch, esphome::packet_transport::PacketTransport, esphome::pca6416a::PCA6416AComponent, esphome::pca9554::PCA9554Component, esphome::pca9685::PCA9685Output, esphome::pcd8544::PCD8544, esphome::pcf85063::PCF85063Component, esphome::pcf8563::PCF8563Component, esphome::pcf8574::PCF8574Component, esphome::pi4ioe5v6408::PI4IOE5V6408Component, esphome::pid::PIDClimate, esphome::pid::PIDClimateSensor, esphome::pipsolar::PipsolarSwitch, esphome::pm1006::PM1006Component, esphome::pm2005::PM2005Component, esphome::pmsa003i::PMSA003IComponent, esphome::pmsx003::PMSX003Component, esphome::pmwcs3::PMWCS3Component, esphome::pn532::PN532, esphome::pn532_i2c::PN532I2C, esphome::pn532_spi::PN532Spi, esphome::pn7150::PN7150, esphome::pn7150_i2c::PN7150I2C, esphome::pn7160::PN7160, esphome::pn7160_i2c::PN7160I2C, esphome::pn7160_spi::PN7160Spi, esphome::power_supply::PowerSupply, esphome::pulse_counter::PulseCounterSensor, esphome::pulse_meter::PulseMeterSensor, esphome::pulse_width::PulseWidthSensor, esphome::pvvx_mithermometer::PVVXDisplay, esphome::pvvx_mithermometer::PVVXMiThermometer, esphome::pylontech::PylontechComponent, esphome::pylontech::PylontechSensor, esphome::pylontech::PylontechTextSensor, esphome::pzem004t::PZEM004T, esphome::pzemac::PZEMAC, esphome::pzemdc::PZEMDC, esphome::qmc5883l::QMC5883LComponent, esphome::qmp6988::QMP6988Component, esphome::qr_code::QrCode, esphome::qspi_dbi::QspiDbi, esphome::qwiic_pir::QwiicPIRComponent, esphome::radon_eye_rd200::RadonEyeRD200, esphome::rc522::RC522, esphome::rc522_i2c::RC522I2C, esphome::rc522_spi::RC522Spi, esphome::remote_base::RemoteReceiverBinarySensorBase, esphome::remote_receiver::RemoteReceiverComponent, esphome::remote_transmitter::RemoteTransmitterComponent, esphome::resistance::ResistanceSensor, esphome::restart::RestartButton, esphome::restart::RestartSwitch, esphome::rf_bridge::RFBridgeComponent, esphome::rotary_encoder::RotaryEncoderSensor, esphome::rp2040_pio_led_strip::RP2040PIOLEDStripLightOutput, esphome::rp2040_pwm::RP2040PWM, esphome::rpi_dpi_rgb::RpiDpiRgb, esphome::rtttl::Rtttl, esphome::ruuvitag::RuuviTag, esphome::safe_mode::SafeModeButton, esphome::safe_mode::SafeModeComponent, esphome::safe_mode::SafeModeSwitch, esphome::scd30::SCD30Component, esphome::scd4x::SCD4XComponent, esphome::sdl::Sdl, esphome::sdm_meter::SDMMeter, esphome::sdp3x::SDP3XComponent, esphome::sds011::SDS011Component, esphome::seeed_mr24hpc1::MR24HPC1Component, esphome::seeed_mr60bha2::MR60BHA2Component, esphome::seeed_mr60fda2::MR60FDA2Component, esphome::selec_meter::SelecMeter, esphome::sen0321_sensor::Sen0321Sensor, esphome::sen21231_sensor::Sen21231Sensor, esphome::sen5x::SEN5XComponent, esphome::senseair::SenseAirComponent, esphome::servo::Servo, esphome::sfa30::SFA30Component, esphome::sgp30::SGP30Component, esphome::sgp4x::SGP4xComponent, esphome::shelly_dimmer::ShellyDimmer, esphome::sht3xd::SHT3XDComponent, esphome::sht4x::SHT4XComponent, esphome::shtcx::SHTCXComponent, esphome::shutdown::ShutdownButton, esphome::shutdown::ShutdownSwitch, esphome::sigma_delta_output::SigmaDeltaOutput, esphome::sim800l::Sim800LComponent, esphome::slow_pwm::SlowPWMOutput, esphome::sm10bit_base::Sm10BitBase, esphome::sm16716::SM16716, esphome::sm2135::SM2135, esphome::sm2235::SM2235, esphome::sm2335::SM2335, esphome::sm300d2::SM300D2Sensor, esphome::sml::Sml, esphome::sml::SmlSensor, esphome::sml::SmlTextSensor, esphome::smt100::SMT100Component, esphome::sn74hc165::SN74HC165Component, esphome::sn74hc595::SN74HC595Component, esphome::sntp::SNTPComponent, esphome::sonoff_d1::SonoffD1Output, esphome::sound_level::SoundLevelComponent, esphome::speed::SpeedFan, esphome::spi::SPIComponent, esphome::spi_device::SPIDeviceComponent, esphome::spi_led_strip::SpiLedStrip, esphome::sprinkler::Sprinkler, esphome::sprinkler::SprinklerControllerNumber, esphome::sprinkler::SprinklerControllerSwitch, esphome::sps30::SPS30Component, esphome::ssd1306_i2c::I2CSSD1306, esphome::ssd1306_spi::SPISSD1306, esphome::ssd1322_spi::SPISSD1322, esphome::ssd1325_spi::SPISSD1325, esphome::ssd1327_i2c::I2CSSD1327, esphome::ssd1327_spi::SPISSD1327, esphome::ssd1331_spi::SPISSD1331, esphome::ssd1351_spi::SPISSD1351, esphome::st7567_i2c::I2CST7567, esphome::st7567_spi::SPIST7567, esphome::st7701s::ST7701S, esphome::st7735::ST7735, esphome::st7789v::ST7789V, esphome::st7920::ST7920, esphome::statsd::StatsdComponent, esphome::status::StatusBinarySensor, esphome::status_led::StatusLED, esphome::status_led::StatusLEDLightOutput, esphome::sts3x::STS3XComponent, esphome::sun::SunSensor, esphome::sun::SunTextSensor, esphome::sun_gtil2::SunGTIL2, esphome::switch_::SwitchBinarySensor, esphome::sx126x::SX126x, esphome::sx127x::SX127x, esphome::sx1509::SX1509Component, esphome::sx1509::SX1509FloatOutputChannel, esphome::t6615::T6615Component, esphome::tc74::TC74Component, esphome::tca9548a::TCA9548AComponent, esphome::tca9555::TCA9555Component, esphome::tcs34725::TCS34725Component, esphome::tee501::TEE501Component, esphome::teleinfo::TeleInfo, esphome::teleinfo::TeleInfoSensor, esphome::teleinfo::TeleInfoTextSensor, esphome::tem3200::TEM3200Component, esphome::template_::TemplateAlarmControlPanel, esphome::template_::TemplateBinarySensor, esphome::template_::TemplateCover, esphome::template_::TemplateDate, esphome::template_::TemplateDateTime, esphome::template_::TemplateFan, esphome::template_::TemplateLock, esphome::template_::TemplateNumber, esphome::template_::TemplateSelect, esphome::template_::TemplateSensor, esphome::template_::TemplateSwitch, esphome::template_::TemplateText, esphome::template_::TemplateTextSensor, esphome::template_::TemplateTime, esphome::template_::TemplateValve, esphome::thermostat::ThermostatClimate, esphome::time_based::TimeBasedCover, esphome::tlc59208f::TLC59208FOutput, esphome::tlc5947::TLC5947, esphome::tlc5971::TLC5971, esphome::tm1621::TM1621Display, esphome::tm1637::TM1637Display, esphome::tm1638::TM1638Component, esphome::tm1638::TM1638OutputLed, esphome::tm1638::TM1638SwitchLed, esphome::tm1651::TM1651Display, esphome::tmp102::TMP102Component, esphome::tmp1075::TMP1075Sensor, esphome::tmp117::TMP117Component, esphome::tof10120::TOF10120Sensor, esphome::tormatic::Tormatic, esphome::total_daily_energy::TotalDailyEnergy, esphome::tsl2561::TSL2561Sensor, esphome::tsl2591::TSL2591Component, esphome::tt21100::TT21100Button, esphome::tt21100::TT21100Touchscreen, esphome::ttp229_bsf::TTP229BSFComponent, esphome::ttp229_lsf::TTP229LSFComponent, esphome::tuya::Tuya, esphome::tuya::TuyaBinarySensor, esphome::tuya::TuyaClimate, esphome::tuya::TuyaCover, esphome::tuya::TuyaFan, esphome::tuya::TuyaLight, esphome::tuya::TuyaNumber, esphome::tuya::TuyaSelect, esphome::tuya::TuyaSensor, esphome::tuya::TuyaSwitch, esphome::tuya::TuyaTextSensor, esphome::tx20::Tx20Component, esphome::uart::ESP32ArduinoUARTComponent, esphome::uart::ESP8266UartComponent, esphome::uart::HostUartComponent, esphome::uart::IDFUARTComponent, esphome::uart::LibreTinyUARTComponent, esphome::uart::RP2040UartComponent, esphome::uart::UARTButton, esphome::uart::UARTSwitch, esphome::udp::UDPComponent, esphome::ufire_ec::UFireECComponent, esphome::ufire_ise::UFireISEComponent, esphome::uln2003::ULN2003, esphome::ultrasonic::UltrasonicSensorComponent, esphome::uponor_smatrix::UponorSmatrixClimate, esphome::uponor_smatrix::UponorSmatrixComponent, esphome::uptime::UptimeSecondsSensor, esphome::uptime::UptimeTextSensor, esphome::uptime::UptimeTimestampSensor, esphome::usb_host::USBClient, esphome::usb_uart::USBUartComponent, esphome::vbus::DeltaSolBS2009BSensor, esphome::vbus::DeltaSolBS2009Sensor, esphome::vbus::DeltaSolBSPlusBSensor, esphome::vbus::DeltaSolBSPlusSensor, esphome::vbus::DeltaSolCBSensor, esphome::vbus::DeltaSolCS2BSensor, esphome::vbus::DeltaSolCS2Sensor, esphome::vbus::DeltaSolCSensor, esphome::vbus::DeltaSolCSPlusBSensor, esphome::vbus::DeltaSolCSPlusSensor, esphome::vbus::VBus, esphome::vbus::VBusCustomBSensor, esphome::vbus::VBusCustomSensor, esphome::veml3235::VEML3235Sensor, esphome::veml7700::VEML7700Component, esphome::version::VersionTextSensor, esphome::vl53l0x::VL53L0XSensor, esphome::wake_on_lan::WakeOnLanButton, esphome::waveshare_epaper::GDEW0154M09, esphome::waveshare_epaper::GDEW029T5, esphome::waveshare_epaper::GDEY029T94, esphome::waveshare_epaper::GDEY042T81, esphome::waveshare_epaper::GDEY0583T81, esphome::waveshare_epaper::WaveshareEPaper13P3InK, esphome::waveshare_epaper::WaveshareEPaper1P54InBV2, esphome::waveshare_epaper::WaveshareEPaper2P13InDKE, esphome::waveshare_epaper::WaveshareEPaper2P13InV3, esphome::waveshare_epaper::WaveshareEPaper2P7In, esphome::waveshare_epaper::WaveshareEPaper2P7InB, esphome::waveshare_epaper::WaveshareEPaper2P7InBV2, esphome::waveshare_epaper::WaveshareEPaper2P7InV2, esphome::waveshare_epaper::WaveshareEPaper2P9InB, esphome::waveshare_epaper::WaveshareEPaper2P9InBV3, esphome::waveshare_epaper::WaveshareEPaper2P9InD, esphome::waveshare_epaper::WaveshareEPaper2P9InDKE, esphome::waveshare_epaper::WaveshareEPaper2P9InV2R2, esphome::waveshare_epaper::WaveshareEPaper4P2In, esphome::waveshare_epaper::WaveshareEPaper4P2InBV2, esphome::waveshare_epaper::WaveshareEPaper4P2InBV2BWR, esphome::waveshare_epaper::WaveshareEPaper5P65InF, esphome::waveshare_epaper::WaveshareEPaper5P8In, esphome::waveshare_epaper::WaveshareEPaper5P8InV2, esphome::waveshare_epaper::WaveshareEPaper7P3InF, esphome::waveshare_epaper::WaveshareEPaper7P5In, esphome::waveshare_epaper::WaveshareEPaper7P5InBC, esphome::waveshare_epaper::WaveshareEPaper7P5InBV2, esphome::waveshare_epaper::WaveshareEPaper7P5InBV3, esphome::waveshare_epaper::WaveshareEPaper7P5InBV3BWR, esphome::waveshare_epaper::WaveshareEPaper7P5InHDB, esphome::waveshare_epaper::WaveshareEPaper7P5InV2, esphome::waveshare_epaper::WaveshareEPaper7P5InV2alt, esphome::waveshare_epaper::WaveshareEPaper7P5InV2P, esphome::waveshare_epaper::WaveshareEPaperTypeA, esphome::web_server::WebServer, esphome::web_server::WebServerOTAComponent, esphome::weikai_i2c::WeikaiComponentI2C, esphome::weikai_spi::WeikaiComponentSPI, esphome::wiegand::Wiegand, esphome::wifi::WiFiComponent, esphome::wifi_info::BSSIDWiFiInfo, esphome::wifi_info::DNSAddressWifiInfo, esphome::wifi_info::IPAddressWiFiInfo, esphome::wifi_info::MacAddressWifiInfo, esphome::wifi_info::ScanResultsWiFiInfo, esphome::wifi_info::SSIDWiFiInfo, esphome::wifi_signal::WiFiSignalSensor, esphome::wireguard::Wireguard, esphome::wl_134::Wl134Component, esphome::x9c::X9cOutput, esphome::xgzp68xx::XGZP68XXComponent, esphome::xiaomi_cgd1::XiaomiCGD1, esphome::xiaomi_cgdk2::XiaomiCGDK2, esphome::xiaomi_cgg1::XiaomiCGG1, esphome::xiaomi_cgpr1::XiaomiCGPR1, esphome::xiaomi_gcls002::XiaomiGCLS002, esphome::xiaomi_hhccjcy01::XiaomiHHCCJCY01, esphome::xiaomi_hhccjcy10::XiaomiHHCCJCY10, esphome::xiaomi_hhccpot002::XiaomiHHCCPOT002, esphome::xiaomi_jqjcy01ym::XiaomiJQJCY01YM, esphome::xiaomi_lywsd02::XiaomiLYWSD02, esphome::xiaomi_lywsd02mmc::XiaomiLYWSD02MMC, esphome::xiaomi_lywsd03mmc::XiaomiLYWSD03MMC, esphome::xiaomi_lywsdcgq::XiaomiLYWSDCGQ, esphome::xiaomi_mhoc303::XiaomiMHOC303, esphome::xiaomi_mhoc401::XiaomiMHOC401, esphome::xiaomi_miscale::XiaomiMiscale, esphome::xiaomi_mjyd02yla::XiaomiMJYD02YLA, esphome::xiaomi_mue4094rt::XiaomiMUE4094RT, esphome::xiaomi_rtcgq02lm::XiaomiRTCGQ02LM, esphome::xiaomi_wx08zm::XiaomiWX08ZM, esphome::xiaomi_xmwsdj04mmc::XiaomiXMWSDJ04MMC, esphome::xl9535::XL9535Component, esphome::xpt2046::XPT2046Component, esphome::zio_ultrasonic::ZioUltrasonicComponent, and esphome::zyaura::ZyAuraSensor.
Definition at line 323 of file component.cpp.
void esphome::Component::enable_loop | ( | ) |
Enable this component's loop.
The loop() method will be called normally.
This is useful for components that transition between active and inactive states and need to re-enable their loop() method when becoming active again.
Definition at line 209 of file component.cpp.
void IRAM_ATTR HOT esphome::Component::enable_loop_soon_any_context | ( | ) |
Thread and ISR-safe version of enable_loop() that can be called from any context.
This method defers the actual enable via enable_pending_loops_ to the main loop, making it safe to call from ISR handlers, timer callbacks, other threads, or any interrupt context.
Use disable_loop() from the main thread only.
If you need to disable the loop from ISR, carefully implement it in the component itself, with an ISR safe approach, and call disable_loop() in its next loop() iteration. Implementations will need to carefully consider all possible race conditions.
Definition at line 217 of file component.cpp.
float esphome::Component::get_actual_setup_priority | ( | ) | const |
Definition at line 324 of file component.cpp.
const char * esphome::Component::get_component_source | ( | ) | const |
Get the integration where this component was declared as a string.
Returns "<unknown>" if source not set
Definition at line 175 of file component.cpp.
uint8_t esphome::Component::get_component_state | ( | ) | const |
Definition at line 145 of file component.cpp.
|
virtual |
priority of loop().
higher -> executed earlier
Defaults to 0.
Reimplemented in esphome::ch422g::CH422GComponent, esphome::deep_sleep::DeepSleepComponent, esphome::pca9554::PCA9554Component, esphome::status_led::StatusLED, esphome::status_led::StatusLEDLightOutput, and esphome::wifi::WiFiComponent.
Definition at line 77 of file component.cpp.
|
virtual |
priority of setup().
higher -> executed earlier
Defaults to setup_priority::DATA, i.e. 600.
Reimplemented in esphome::a4988::A4988, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::adc128s102::ADC128S102, esphome::adc128s102::ADC128S102Sensor, esphome::adc::ADCSensor, esphome::aht10::AHT10Component, esphome::am2315c::AM2315C, esphome::am2320::AM2320Component, esphome::apds9306::APDS9306, esphome::api::APIServer, esphome::as5600::AS5600Sensor, esphome::as7341::AS7341Component, esphome::atm90e26::ATM90E26Component, esphome::atm90e32::ATM90E32Component, esphome::bedjet::BedJetClimate, esphome::bedjet::BedJetFan, esphome::bedjet::BedJetHub, esphome::beken_spi_led_strip::BekenSPILEDStripLightOutput, esphome::bh1750::BH1750Sensor, esphome::binary_sensor::AutorepeatFilter, esphome::binary_sensor::DelayedOffFilter, esphome::binary_sensor::DelayedOnFilter, esphome::binary_sensor::DelayedOnOffFilter, esphome::binary_sensor::MultiClickTrigger, esphome::binary_sensor::SettleFilter, esphome::bme280_base::BME280Component, esphome::bme680::BME680Component, esphome::bme680_bsec::BME680BSECComponent, esphome::bme68x_bsec2::BME68xBSEC2Component, esphome::bmi160::BMI160Component, esphome::bmp085::BMP085Component, esphome::bmp280_base::BMP280Component, esphome::bmp3xx_base::BMP3XXComponent, esphome::bp1658cj::BP1658CJ, esphome::bp5758d::BP5758D, esphome::canbus::Canbus, esphome::captive_portal::CaptivePortal, esphome::cd74hc4067::CD74HC4067Component, esphome::cd74hc4067::CD74HC4067Sensor, esphome::ch422g::CH422GComponent, esphome::cm1106::CM1106Component, esphome::combination::CombinationComponent, esphome::cse7761::CSE7761Component, esphome::cse7766::CSE7766Component, esphome::ct_clamp::CTClampSensor, esphome::current_based::CurrentBasedCover, esphome::dac7678::DAC7678Output, esphome::daly_bms::DalyBmsComponent, esphome::debug::DebugComponent, esphome::deep_sleep::DeepSleepComponent, esphome::DelayAction< Ts >, esphome::dht12::DHT12Component, esphome::dht::DHT, esphome::display_menu_base::DisplayMenuComponent, esphome::dps310::DPS310Component, esphome::ds1307::DS1307Component, esphome::ds2484::DS2484OneWireBus, esphome::duty_cycle::DutyCycleSensor, esphome::e131::E131Component, esphome::ee895::EE895Component, esphome::emc2101::Emc2101Component, esphome::emc2101::EMC2101Sensor, esphome::endstop::EndstopCover, esphome::ens210::ENS210Component, esphome::esp32_ble::ESP32BLE, esphome::esp32_ble_beacon::ESP32BLEBeacon, esphome::esp32_ble_client::BLEClientBase, esphome::esp32_ble_server::BLEServer, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::esp32_camera::ESP32Camera, esphome::esp32_camera_web_server::CameraWebServer, esphome::esp32_dac::ESP32DAC, esphome::esp32_improv::ESP32ImprovComponent, esphome::esp32_rmt_led_strip::ESP32RMTLEDStripLightOutput, esphome::esp32_touch::ESP32TouchComponent, esphome::esp8266_pwm::ESP8266PWM, esphome::esp_ldo::EspLdo, esphome::ESPHomeOTAComponent, esphome::ethernet::EthernetComponent, esphome::ethernet_info::DNSAddressEthernetInfo, esphome::ethernet_info::IPAddressEthernetInfo, esphome::ethernet_info::MACAddressEthernetInfo, esphome::fastled_base::FastLEDLightOutput, esphome::ForCondition< Ts >, esphome::globals::RestoringGlobalsComponent< T >, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::gp2y1010au0f::GP2Y1010AU0FSensor, esphome::gp8403::GP8403Output, esphome::gpio::GPIOBinaryOutput, esphome::gpio::GPIOBinarySensor, esphome::gpio::GPIOOneWireBus, esphome::gpio::GPIOSwitch, esphome::gps::GPS, esphome::graph::Graph, esphome::haier::HaierClimateBase, esphome::hbridge::HBridgeLightOutput, esphome::hbridge::HBridgeSwitch, esphome::hdc1080::HDC1080Component, esphome::hlw8012::HLW8012Component, esphome::hm3301::HM3301Component, esphome::hmc5883l::HMC5883LComponent, esphome::homeassistant::HomeassistantBinarySensor, esphome::homeassistant::HomeassistantNumber, esphome::homeassistant::HomeassistantSensor, esphome::homeassistant::HomeassistantSwitch, esphome::homeassistant::HomeassistantTextSensor, esphome::homeassistant::HomeassistantTime, esphome::honeywell_hih_i2c::HoneywellHIComponent, esphome::honeywellabp::HONEYWELLABPSensor, esphome::hte501::HTE501Component, esphome::http_request::HttpRequestComponent, esphome::http_request::HttpRequestUpdate, esphome::http_request::OtaHttpRequestComponent, esphome::htu21d::HTU21DComponent, esphome::htu31d::HTU31DComponent, esphome::hx711::HX711Sensor, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::hyt271::HYT271Component, esphome::i2c::ArduinoI2CBus, esphome::i2c::IDFI2CBus, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::i2s_audio::I2SAudioSpeaker, esphome::ili9xxx::ILI9XXXDisplay, esphome::improv_serial::ImprovSerialComponent, esphome::ina219::INA219Component, esphome::ina226::INA226Component, esphome::ina2xx_base::INA2XX, esphome::ina3221::INA3221Component, esphome::inkplate6::Inkplate6, esphome::kamstrup_kmp::KamstrupKMPComponent, esphome::kmeteriso::KMeterISOComponent, esphome::lcd_base::LCDDisplay, esphome::lcd_menu::LCDCharacterMenuComponent, esphome::ld2420::LD2420Component, esphome::ledc::LEDCOutput, esphome::libretiny::LTComponent, esphome::libretiny_pwm::LibreTinyPWM, esphome::light::LightState, esphome::logger::Logger, esphome::LoopTrigger, esphome::lvgl::LvglComponent, esphome::m5stack_8angle::M5Stack8AngleComponent, esphome::max17043::MAX17043Component, esphome::max31855::MAX31855Sensor, esphome::max31856::MAX31856Sensor, esphome::max31865::MAX31865Sensor, esphome::max44009::MAX44009Sensor, esphome::max6675::MAX6675Sensor, esphome::max6956::MAX6956, esphome::max6956::MAX6956LedChannel, esphome::max7219::MAX7219Component, esphome::max7219digit::MAX7219Component, esphome::mcp23016::MCP23016, esphome::mcp23xxx_base::MCP23XXXBase, esphome::mcp3008::MCP3008, esphome::mcp3008::MCP3008Sensor, esphome::mcp3204::MCP3204, esphome::mcp3204::MCP3204Sensor, esphome::mcp4461::Mcp4461Component, esphome::mcp4728::MCP4728Component, esphome::mcp9808::MCP9808Sensor, esphome::mdns::MDNSComponent, esphome::mhz19::MHZ19Component, esphome::micro_wake_word::MicroWakeWord, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::mlx90393::MLX90393Cls, esphome::mlx90614::MLX90614Component, esphome::mmc5603::MMC5603Component, esphome::mmc5983::MMC5983Component, esphome::modbus::Modbus, esphome::modbus_controller::ModbusNumber, esphome::mpr121::MPR121Component, esphome::mpu6050::MPU6050Component, esphome::mpu6886::MPU6886Component, esphome::mqtt::MQTTClientComponent, esphome::mqtt::MQTTComponent, esphome::mqtt::MQTTMessageTrigger, esphome::mqtt_subscribe::MQTTSubscribeSensor, esphome::mqtt_subscribe::MQTTSubscribeTextSensor, esphome::ms5611::MS5611Component, esphome::msa3xx::MSA3xxComponent, esphome::my9231::MY9231OutputComponent, esphome::nau7802::NAU7802Sensor, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, T_COLOR_FEATURE >, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, NeoRgbFeature >, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, NeoRgbwFeature >, esphome::nextion::Nextion, esphome::npi19::NPI19Component, esphome::ntc::NTC, esphome::number::ValueRangeTrigger, esphome::opentherm::OpenthermHub, esphome::openthread::OpenThreadComponent, esphome::openthread::OpenThreadSrpComponent, esphome::openthread_info::ChannelOpenThreadInfo, esphome::openthread_info::Eui64OpenThreadInfo, esphome::openthread_info::ExtAddrOpenThreadInfo, esphome::openthread_info::ExtPanIdOpenThreadInfo, esphome::openthread_info::IPAddressOpenThreadInfo, esphome::openthread_info::NetworkKeyOpenThreadInfo, esphome::openthread_info::NetworkNameOpenThreadInfo, esphome::openthread_info::OpenThreadInstancePollingComponent, esphome::openthread_info::PanIdOpenThreadInfo, esphome::openthread_info::Rloc16OpenThreadInfo, esphome::opt3001::OPT3001Sensor, esphome::output::OutputLock, esphome::output::OutputSwitch, esphome::pca6416a::PCA6416AComponent, esphome::pca9554::PCA9554Component, esphome::pca9685::PCA9685Output, esphome::pcd8544::PCD8544, esphome::pcf85063::PCF85063Component, esphome::pcf8563::PCF8563Component, esphome::pcf8574::PCF8574Component, esphome::pi4ioe5v6408::PI4IOE5V6408Component, esphome::pm1006::PM1006Component, esphome::pm2005::PM2005Component, esphome::pmwcs3::PMWCS3Component, esphome::pn532::PN532, esphome::power_supply::PowerSupply, esphome::preferences::IntervalSyncer, esphome::ProjectUpdateTrigger, esphome::prometheus::PrometheusHandler, esphome::pulse_meter::PulseMeterSensor, esphome::pylontech::PylontechComponent, esphome::qmc5883l::QMC5883LComponent, esphome::qmp6988::QMP6988Component, esphome::remote_transmitter::RemoteTransmitterComponent, esphome::resampler::ResamplerSpeaker, esphome::rotary_encoder::RotaryEncoderSensor, esphome::rp2040_pio_led_strip::RP2040PIOLEDStripLightOutput, esphome::rp2040_pwm::RP2040PWM, esphome::rpi_dpi_rgb::RpiDpiRgb, esphome::safe_mode::SafeModeComponent, esphome::sdl::Sdl, esphome::sdp3x::SDP3XComponent, esphome::sds011::SDS011Component, esphome::seeed_mr24hpc1::MR24HPC1Component, esphome::seeed_mr60bha2::MR60BHA2Component, esphome::seeed_mr60fda2::MR60FDA2Component, esphome::sensor::DebounceFilter, esphome::sensor::HeartbeatFilter, esphome::sensor::ThrottleAverageFilter, esphome::sensor::TimeoutFilter, esphome::sensor::ValueRangeTrigger, esphome::shelly_dimmer::ShellyDimmer, esphome::sht3xd::SHT3XDComponent, esphome::shtcx::SHTCXComponent, esphome::ShutdownTrigger, esphome::slow_pwm::SlowPWMOutput, esphome::sm10bit_base::Sm10BitBase, esphome::sm16716::SM16716, esphome::sm2135::SM2135, esphome::smt100::SMT100Component, esphome::sn74hc165::SN74HC165Component, esphome::sn74hc595::SN74HC595Component, esphome::sntp::SNTPComponent, esphome::sonoff_d1::SonoffD1Output, esphome::sound_level::SoundLevelComponent, esphome::speaker::SpeakerMediaPlayer, esphome::spi::SPIComponent, esphome::spi_device::SPIDeviceComponent, esphome::spi_led_strip::SpiLedStrip, esphome::sprinkler::SprinklerControllerNumber, esphome::sprinkler::SprinklerControllerSwitch, esphome::ssd1306_base::SSD1306, esphome::ssd1322_base::SSD1322, esphome::ssd1325_base::SSD1325, esphome::ssd1327_base::SSD1327, esphome::ssd1331_base::SSD1331, esphome::ssd1351_base::SSD1351, esphome::st7567_base::ST7567, esphome::st7735::ST7735, esphome::st7789v::ST7789V, esphome::st7920::ST7920, esphome::StartupTrigger, esphome::statsd::StatsdComponent, esphome::status_led::StatusLED, esphome::status_led::StatusLEDLightOutput, esphome::sts3x::STS3XComponent, esphome::sun_gtil2::SunGTIL2, esphome::sx126x::SX126x, esphome::sx126x::SX126xTransport, esphome::sx127x::SX127x, esphome::sx127x::SX127xTransport, esphome::sx1509::SX1509Component, esphome::sx1509::SX1509FloatOutputChannel, esphome::t6615::T6615Component, esphome::tc74::TC74Component, esphome::tca9548a::TCA9548AComponent, esphome::tca9555::TCA9555Component, esphome::tcs34725::TCS34725Component, esphome::tee501::TEE501Component, esphome::tem3200::TEM3200Component, esphome::template_::TemplateBinarySensor, esphome::template_::TemplateCover, esphome::template_::TemplateDate, esphome::template_::TemplateDateTime, esphome::template_::TemplateLock, esphome::template_::TemplateNumber, esphome::template_::TemplateSelect, esphome::template_::TemplateSensor, esphome::template_::TemplateSwitch, esphome::template_::TemplateText, esphome::template_::TemplateTextSensor, esphome::template_::TemplateTime, esphome::template_::TemplateValve, esphome::time::CronTrigger, esphome::time_based::TimeBasedCover, esphome::tlc59208f::TLC59208FOutput, esphome::tlc5947::TLC5947, esphome::tlc5971::TLC5971, esphome::tm1621::TM1621Display, esphome::tm1637::TM1637Display, esphome::tm1638::TM1638Component, esphome::tmp102::TMP102Component, esphome::tmp117::TMP117Component, esphome::tsl2561::TSL2561Sensor, esphome::tsl2591::TSL2591Component, esphome::tt21100::TT21100Touchscreen, esphome::tuya::Tuya, esphome::tx20::Tx20Component, esphome::uart::ESP32ArduinoUARTComponent, esphome::uart::ESP8266UartComponent, esphome::uart::HostUartComponent, esphome::uart::IDFUARTComponent, esphome::uart::LibreTinyUARTComponent, esphome::uart::RP2040UartComponent, esphome::uart::UARTTransport, esphome::udp::UDPComponent, esphome::udp::UDPTransport, esphome::uln2003::ULN2003, esphome::ultrasonic::UltrasonicSensorComponent, esphome::uptime::UptimeSecondsSensor, esphome::uptime::UptimeTextSensor, esphome::uptime::UptimeTimestampSensor, esphome::usb_host::USBClient, esphome::usb_host::USBHost, esphome::version::VersionTextSensor, esphome::voice_assistant::VoiceAssistant, esphome::WaitUntilAction< Ts >, esphome::wake_on_lan::WakeOnLanButton, esphome::waveshare_epaper::WaveshareEPaperBase, esphome::web_server::WebServer, esphome::web_server::WebServerOTAComponent, esphome::web_server_base::WebServerBase, esphome::weikai::WeikaiComponent, esphome::wiegand::Wiegand, esphome::wifi::WiFiComponent, esphome::wifi_info::BSSIDWiFiInfo, esphome::wifi_info::DNSAddressWifiInfo, esphome::wifi_info::IPAddressWiFiInfo, esphome::wifi_info::ScanResultsWiFiInfo, esphome::wifi_info::SSIDWiFiInfo, esphome::wifi_signal::WiFiSignalSensor, esphome::wireguard::Wireguard, and esphome::xl9535::XL9535Component.
Definition at line 79 of file component.cpp.
bool esphome::Component::has_overridden_loop | ( | ) | const |
Definition at line 356 of file component.cpp.
bool esphome::Component::is_failed | ( | ) | const |
Definition at line 264 of file component.cpp.
bool esphome::Component::is_in_loop_state | ( | ) | const |
Check if this component has completed setup and is in the loop state.
Definition at line 239 of file component.cpp.
bool esphome::Component::is_ready | ( | ) | const |
Definition at line 265 of file component.cpp.
|
virtual |
This method will be called repeatedly.
Analogous to Arduino's loop(). setup() is guaranteed to be called before this. Defaults to doing nothing.
Reimplemented in esphome::a01nyub::A01nyubComponent, esphome::a02yyuw::A02yyuwComponent, esphome::a4988::A4988, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::ade7880::ADE7880, esphome::am43::Am43Component, esphome::anova::Anova, esphome::api::APIServer, esphome::atm90e32::ATM90E32Component, esphome::bedjet::BedJetClimate, esphome::bedjet::BedJetHub, esphome::binary_sensor_map::BinarySensorMap, esphome::bl0939::BL0939, esphome::bl0940::BL0940, esphome::bl0942::BL0942, esphome::ble_client::BLEBinaryOutput, esphome::ble_client::BLEClient, esphome::ble_client::BLEClientRSSISensor, esphome::ble_client::BLEClientSwitch, esphome::ble_client::BLESensor, esphome::ble_client::BLETextSensor, esphome::ble_presence::BLEPresenceDevice, esphome::bluetooth_proxy::BluetoothProxy, esphome::bme680_bsec::BME680BSECComponent, esphome::bme68x_bsec2::BME68xBSEC2Component, esphome::bp1658cj::BP1658CJ, esphome::bp5758d::BP5758D, esphome::canbus::Canbus, esphome::cap1188::CAP1188Component, esphome::captive_portal::CaptivePortal, esphome::ch422g::CH422GComponent, esphome::cs5460a::CS5460AComponent, esphome::cse7766::CSE7766Component, esphome::ct_clamp::CTClampSensor, esphome::current_based::CurrentBasedCover, esphome::daly_bms::DalyBmsComponent, esphome::datetime::OnDateTimeTrigger, esphome::datetime::OnTimeTrigger, esphome::debug::DebugComponent, esphome::deep_sleep::DeepSleepComponent, esphome::dfplayer::DFPlayer, esphome::dsmr::Dsmr, esphome::duty_time_sensor::DutyTimeSensor, esphome::e131::E131Component, esphome::endstop::EndstopCover, esphome::esp32_ble::ESP32BLE, esphome::esp32_ble_client::BLEClientBase, esphome::esp32_ble_server::BLEServer, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::esp32_camera::ESP32Camera, esphome::esp32_camera_web_server::CameraWebServer, esphome::esp32_improv::ESP32ImprovComponent, esphome::esp32_touch::ESP32TouchComponent, esphome::ESPHomeOTAComponent, esphome::ethernet::EthernetComponent, esphome::ezo::EZOSensor, esphome::ezo_pmp::EzoPMP, esphome::feedback::FeedbackCover, esphome::ForCondition< Ts >, esphome::gcja5::GCJA5Component, esphome::globals::RestoringGlobalsComponent< T >, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::gp2y1010au0f::GP2Y1010AU0FSensor, esphome::gpio::GPIOBinarySensor, esphome::gps::GPS, esphome::growatt_solar::GrowattSolar, esphome::haier::HaierClimateBase, esphome::he60r::HE60rCover, esphome::honeywell_hih_i2c::HoneywellHIComponent, esphome::honeywellabp2_i2c::HONEYWELLABP2Sensor, esphome::hrxl_maxsonar_wr::HrxlMaxsonarWrComponent, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::i2s_audio::I2SAudioMicrophone, esphome::i2s_audio::I2SAudioSpeaker, esphome::improv_serial::ImprovSerialComponent, esphome::ina2xx_base::INA2XX, esphome::jsn_sr04t::Jsnsr04tComponent, esphome::kamstrup_kmp::KamstrupKMPComponent, esphome::key_collector::KeyCollector, esphome::kuntze::Kuntze, esphome::ld2420::LD2420Component, esphome::light::LightState, esphome::logger::Logger, esphome::LoopTrigger, esphome::ltr501::LTRAlsPs501Component, esphome::ltr_als_ps::LTRAlsPsComponent, esphome::lvgl::LvglComponent, esphome::matrix_keypad::MatrixKeypad, esphome::max7219digit::MAX7219Component, esphome::mcp4461::Mcp4461Component, esphome::mcp4728::MCP4728Component, esphome::mdns::MDNSComponent, esphome::micro_wake_word::MicroWakeWord, esphome::micronova::MicroNova, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::mixer_speaker::MixerSpeaker, esphome::mixer_speaker::SourceSpeaker, esphome::modbus::Modbus, esphome::modbus_controller::ModbusController, esphome::mpr121::MPR121Component, esphome::mqtt::MQTTClientComponent, esphome::msa3xx::MSA3xxComponent, esphome::my9231::MY9231OutputComponent, esphome::nau7802::NAU7802Sensor, esphome::nextion::Nextion, esphome::online_image::OnlineImage, esphome::opentherm::OpenthermHub, esphome::packet_transport::PacketTransport, esphome::pca9554::PCA9554Component, esphome::pca9685::PCA9685Output, esphome::pi4ioe5v6408::PI4IOE5V6408Component, esphome::pm1006::PM1006Component, esphome::pmsx003::PMSX003Component, esphome::pn532::PN532, esphome::pn7150::PN7150, esphome::pn7160::PN7160, esphome::preferences::IntervalSyncer, esphome::pulse_meter::PulseMeterSensor, esphome::pylontech::PylontechComponent, esphome::pzem004t::PZEM004T, esphome::qwiic_pir::QwiicPIRComponent, esphome::rc522::RC522, esphome::rdm6300::RDM6300Component, esphome::remote_receiver::RemoteReceiverComponent, esphome::resampler::ResamplerSpeaker, esphome::rf_bridge::RFBridgeComponent, esphome::rotary_encoder::RotaryEncoderSensor, esphome::rpi_dpi_rgb::RpiDpiRgb, esphome::rtttl::Rtttl, esphome::safe_mode::SafeModeComponent, esphome::script::QueueingScript< Ts >, esphome::script::ScriptWaitAction< C, Ts >, esphome::sdl::Sdl, esphome::sds011::SDS011Component, esphome::seeed_mr24hpc1::MR24HPC1Component, esphome::seeed_mr60bha2::MR60BHA2Component, esphome::seeed_mr60fda2::MR60FDA2Component, esphome::servo::Servo, esphome::sim800l::Sim800LComponent, esphome::slow_pwm::SlowPWMOutput, esphome::sm10bit_base::Sm10BitBase, esphome::sm16716::SM16716, esphome::sm2135::SM2135, esphome::sml::Sml, esphome::smt100::SMT100Component, esphome::sn74hc165::SN74HC165Component, esphome::sntp::SNTPComponent, esphome::sonoff_d1::SonoffD1Output, esphome::sound_level::SoundLevelComponent, esphome::speaker::SpeakerMediaPlayer, esphome::sprinkler::Sprinkler, esphome::sprinkler::SprinklerControllerSwitch, esphome::st7701s::ST7701S, esphome::status::StatusBinarySensor, esphome::status_led::StatusLED, esphome::status_led::StatusLEDLightOutput, esphome::sun_gtil2::SunGTIL2, esphome::sx126x::SX126x, esphome::sx127x::SX127x, esphome::sx1509::SX1509Component, esphome::t6615::T6615Component, esphome::tca9555::TCA9555Component, esphome::teleinfo::TeleInfo, esphome::template_::TemplateAlarmControlPanel, esphome::template_::TemplateBinarySensor, esphome::template_::TemplateCover, esphome::template_::TemplateLock, esphome::template_::TemplateSwitch, esphome::template_::TemplateValve, esphome::thermostat::ThermostatClimate, esphome::time::CronTrigger, esphome::time_based::TimeBasedCover, esphome::tlc59208f::TLC59208FOutput, esphome::tlc5947::TLC5947, esphome::tlc5971::TLC5971, esphome::tm1637::TM1637Display, esphome::tm1638::TM1638Component, esphome::tormatic::Tormatic, esphome::total_daily_energy::TotalDailyEnergy, esphome::touchscreen::Touchscreen, esphome::ttp229_bsf::TTP229BSFComponent, esphome::ttp229_lsf::TTP229LSFComponent, esphome::tuya::Tuya, esphome::tuya::TuyaClimate, esphome::tx20::Tx20Component, esphome::uart::UARTDebugger, esphome::uart::UARTDummyReceiver, esphome::uart::UARTSwitch, esphome::uart::UARTTransport, esphome::udp::UDPComponent, esphome::uln2003::ULN2003, esphome::uponor_smatrix::UponorSmatrixClimate, esphome::uponor_smatrix::UponorSmatrixComponent, esphome::usb_host::USBClient, esphome::usb_host::USBHost, esphome::usb_uart::USBUartComponent, esphome::vbus::VBus, esphome::veml7700::VEML7700Component, esphome::vl53l0x::VL53L0XSensor, esphome::voice_assistant::VoiceAssistant, esphome::WaitUntilAction< Ts >, esphome::web_server::WebServer, esphome::weikai::WeikaiComponent, esphome::wiegand::Wiegand, esphome::wifi::WiFiComponent, esphome::wireguard::Wireguard, and esphome::wl_134::Wl134Component.
Definition at line 83 of file component.cpp.
|
virtual |
Mark this component as failed.
Any future timeouts/intervals/setup/loop will no longer be called.
This might be useful if a component wants to indicate that a connection to its peripheral failed. For example, i2c based components can check if the remote device is responding and otherwise mark the component as failed. Eventually this will also enable smart status LEDs.
Definition at line 193 of file component.cpp.
|
inline |
Definition at line 149 of file component.h.
|
inlinevirtual |
Called after teardown is complete to power down hardware.
This is called after all components have finished their teardown process, making it safe to power down hardware like ethernet PHY.
Reimplemented in esphome::ethernet::EthernetComponent, esphome::ili9xxx::ILI9XXXDisplay, esphome::ina219::INA219Component, esphome::pn532::PN532, and esphome::power_supply::PowerSupply.
Definition at line 125 of file component.h.
|
inlinevirtual |
Reimplemented in esphome::esp32_dac::ESP32DAC, esphome::safe_mode::SafeModeComponent, and esphome::waveshare_epaper::WaveshareEPaperBase.
Definition at line 112 of file component.h.
|
inlinevirtual |
Reimplemented in esphome::api::APIServer, esphome::debug::DebugComponent, esphome::esp32_camera_web_server::CameraWebServer, esphome::esp32_touch::ESP32TouchComponent, esphome::globals::RestoringGlobalsComponent< T >, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::mdns::MDNSComponent, esphome::mqtt::MQTTClientComponent, esphome::opentherm::OpenthermHub, esphome::preferences::IntervalSyncer, esphome::ShutdownTrigger, and esphome::wireguard::Wireguard.
Definition at line 111 of file component.h.
void esphome::Component::reset_to_construction_state | ( | ) |
Reset this component back to the construction state to allow setup to run again.
This can be used by components that have recoverable failures to attempt setup again.
Definition at line 230 of file component.cpp.
|
inline |
Set where this component was loaded from for some debug messages.
This is set by the ESPHome core, and should not be called manually.
Definition at line 223 of file component.h.
|
protected |
Set an interval function with a const char* name.
IMPORTANT: The provided name pointer must remain valid for the lifetime of the scheduler item. This means the name should be:
For dynamic strings, use the std::string overload instead.
name | The identifier for this interval function (must have static lifetime) |
interval | The interval in ms |
f | The function to call |
Definition at line 89 of file component.cpp.
|
protected |
Set an interval function with a unique name.
Empty name means no cancelling possible.
This will call f every interval ms. Can be cancelled via CancelInterval(). Similar to javascript's setInterval().
IMPORTANT NOTE: The only guarantee offered by this call is that the callback will be called no earlier than the specified interval after the previous call. Any given interval may be longer due to other components blocking the loop() call.
So do not rely on this having correct timing. If you need exact timing please use hardware timers.
Note also that the first call to f will not happen immediately, but after a random delay. This is intended to prevent many interval functions from being called at the same time.
name | The identifier for this interval function. |
interval | The interval in ms. |
f | The function (or lambda) that should be called |
Definition at line 85 of file component.cpp.
|
protected |
Definition at line 257 of file component.cpp.
|
protected |
Set an retry function with a unique name.
Empty name means no cancelling possible.
This will call the retry function f on the next scheduler loop. f should return RetryResult::DONE if it is successful and no repeat is required. Otherwise, returning RetryResult::RETRY will call f again in the future.
The first retry of f happens after initial_wait_time
milliseconds. The delay between retries is increased by multiplying by backoff_increase_factor
each time. If no backoff_increase_factor is supplied (default = 1.0), the wait time will stay constant.
The retry function f needs to accept a single argument: the number of attempts remaining. On the final retry of f, this value will be 0.
This retry function can also be cancelled by name via cancel_retry().
IMPORTANT: Do not rely on this having correct timing. This is only called from loop() and therefore can be significantly delayed.
REMARK: It is an error to supply a negative or zero backoff_increase_factor
, and 1.0 will be used instead.
REMARK: The interval between retries is stored into a uint32_t
, so this doesn't behave correctly if initial_wait_time * (backoff_increase_factor ** (max_attempts - 2))
overflows.
name | The identifier for this retry function. |
initial_wait_time | The time in ms before f is called again |
max_attempts | The maximum number of executions |
f | The function (or lambda) that should be called |
backoff_increase_factor | time between retries is multiplied by this factor on every retry after the first |
Definition at line 101 of file component.cpp.
|
protected |
Definition at line 260 of file component.cpp.
void esphome::Component::set_setup_priority | ( | float | priority | ) |
Definition at line 336 of file component.cpp.
|
protected |
Set a timeout function with a const char* name.
IMPORTANT: The provided name pointer must remain valid for the lifetime of the scheduler item. This means the name should be:
For dynamic strings, use the std::string overload instead.
name | The identifier for this timeout function (must have static lifetime) |
timeout | The timeout in ms |
f | The function to call |
Definition at line 114 of file component.cpp.
|
protected |
Set a timeout function with a unique name.
Similar to javascript's setTimeout(). Empty name means no cancelling possible.
IMPORTANT: Do not rely on this having correct timing. This is only called from loop() and therefore can be significantly delay. If you need exact timing please use hardware timers.
name | The identifier for this timeout function. |
timeout | The timeout in ms. |
f | The function (or lambda) that should be called |
Definition at line 110 of file component.cpp.
|
protected |
Definition at line 254 of file component.cpp.
|
virtual |
Where the component's initialization should happen.
Analogous to Arduino's setup(). This method is guaranteed to only be called once. Defaults to doing nothing.
Reimplemented in esphome::a4988::A4988, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::ac_dimmer::AcDimmer, esphome::adc128s102::ADC128S102, esphome::adc::ADCSensor, esphome::addressable_light::AddressableLightDisplay, esphome::ade7880::ADE7880, esphome::ade7953_base::ADE7953, esphome::ade7953_spi::AdE7953Spi, esphome::ads1115::ADS1115Component, esphome::ads1118::ADS1118, esphome::ags10::AGS10Component, esphome::aht10::AHT10Component, esphome::aic3204::AIC3204, esphome::alpha3::Alpha3, esphome::am2315c::AM2315C, esphome::am2320::AM2320Component, esphome::am43::Am43, esphome::am43::Am43Component, esphome::analog_threshold::AnalogThresholdBinarySensor, esphome::anova::Anova, esphome::apds9306::APDS9306, esphome::api::APIServer, esphome::as3935_spi::SPIAS3935Component, esphome::as5600::AS5600Component, esphome::as7341::AS7341Component, esphome::at581x::AT581XComponent, esphome::atm90e26::ATM90E26Component, esphome::atm90e32::ATM90E32Component, esphome::axs15231::AXS15231Touchscreen, esphome::bang_bang::BangBangClimate, esphome::bedjet::BedJetClimate, esphome::bedjet::BedJetHub, esphome::beken_spi_led_strip::BekenSPILEDStripLightOutput, esphome::bh1750::BH1750Sensor, esphome::binary::BinaryFan, esphome::binary_sensor::MultiClickTrigger, esphome::bl0939::BL0939, esphome::bl0940::BL0940, esphome::bl0942::BL0942, esphome::ble_client::BLEClient, esphome::bluetooth_proxy::BluetoothProxy, esphome::bme280_base::BME280Component, esphome::bme680::BME680Component, esphome::bme680_bsec::BME680BSECComponent, esphome::bme68x_bsec2::BME68xBSEC2Component, esphome::bmi160::BMI160Component, esphome::bmp085::BMP085Component, esphome::bmp280_base::BMP280Component, esphome::bmp3xx_base::BMP3XXComponent, esphome::bmp581::BMP581Component, esphome::bp1658cj::BP1658CJ, esphome::bp5758d::BP5758D, esphome::canbus::Canbus, esphome::canbus::CanbusTrigger, esphome::cap1188::CAP1188Component, esphome::captive_portal::CaptivePortal, esphome::ccs811::CCS811Component, esphome::cd74hc4067::CD74HC4067Component, esphome::ch422g::CH422GComponent, esphome::chsc6x::CHSC6XTouchscreen, esphome::climate_ir::ClimateIR, esphome::cm1106::CM1106Component, esphome::combination::CombinationNoParameterComponent, esphome::combination::KalmanCombinationComponent, esphome::combination::LinearCombinationComponent, esphome::copy::CopyBinarySensor, esphome::copy::CopyCover, esphome::copy::CopyFan, esphome::copy::CopyLock, esphome::copy::CopyNumber, esphome::copy::CopySelect, esphome::copy::CopySensor, esphome::copy::CopySwitch, esphome::copy::CopyText, esphome::copy::CopyTextSensor, esphome::cs5460a::CS5460AComponent, esphome::cse7761::CSE7761Component, esphome::cst226::CST226Button, esphome::cst226::CST226Touchscreen, esphome::cst816::CST816Touchscreen, esphome::current_based::CurrentBasedCover, esphome::dac7678::DAC7678Output, esphome::daikin_arc::DaikinArcClimate, esphome::dallas_temp::DallasTemperatureSensor, esphome::deep_sleep::DeepSleepComponent, esphome::demo::DemoAlarmControlPanel, esphome::demo::DemoBinarySensor, esphome::demo::DemoClimate, esphome::demo::DemoCover, esphome::demo::DemoDate, esphome::demo::DemoDateTime, esphome::demo::DemoNumber, esphome::demo::DemoSwitch, esphome::demo::DemoText, esphome::demo::DemoTime, esphome::dht12::DHT12Component, esphome::dht::DHT, esphome::dps310::DPS310Component, esphome::ds1307::DS1307Component, esphome::ds2484::DS2484OneWireBus, esphome::dsmr::Dsmr, esphome::duty_cycle::DutyCycleSensor, esphome::duty_time_sensor::DutyTimeSensor, esphome::e131::E131Component, esphome::ee895::EE895Component, esphome::ektf2232::EKTF2232Touchscreen, esphome::emc2101::Emc2101Component, esphome::endstop::EndstopCover, esphome::ens160_base::ENS160Component, esphome::ens210::ENS210Component, esphome::es7210::ES7210, esphome::es7243e::ES7243E, esphome::es8156::ES8156, esphome::es8311::ES8311, esphome::esp32_ble::ESP32BLE, esphome::esp32_ble_beacon::ESP32BLEBeacon, esphome::esp32_ble_client::BLEClientBase, esphome::esp32_ble_server::BLEServer, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::esp32_camera::ESP32Camera, esphome::esp32_camera_web_server::CameraWebServer, esphome::esp32_dac::ESP32DAC, esphome::esp32_improv::ESP32ImprovComponent, esphome::esp32_rmt_led_strip::ESP32RMTLEDStripLightOutput, esphome::esp32_touch::ESP32TouchComponent, esphome::esp8266_pwm::ESP8266PWM, esphome::esp_ldo::EspLdo, esphome::ESPHomeOTAComponent, esphome::ethernet::EthernetComponent, esphome::ethernet_info::MACAddressEthernetInfo, esphome::fastled_base::FastLEDLightOutput, esphome::feedback::FeedbackCover, esphome::fingerprint_grow::FingerprintGrowComponent, esphome::fs3000::FS3000Component, esphome::ft5x06::FT5x06Touchscreen, esphome::ft63x6::FT63X6Touchscreen, esphome::gl_r01_i2c::GLR01I2CComponent, esphome::globals::GlobalsComponent< T >, esphome::globals::RestoringGlobalsComponent< T >, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::gp8403::GP8403, esphome::gpio::GPIOBinaryOutput, esphome::gpio::GPIOBinarySensor, esphome::gpio::GPIOOneWireBus, esphome::gpio::GPIOSwitch, esphome::graph::Graph, esphome::graphical_display_menu::GraphicalDisplayMenu, esphome::grove_tb6612fng::GroveMotorDriveTB6612FNG, esphome::gt911::GT911Button, esphome::gt911::GT911Touchscreen, esphome::haier::HaierClimateBase, esphome::hbridge::HBridgeFan, esphome::hbridge::HBridgeLightOutput, esphome::hbridge::HBridgeSwitch, esphome::hdc1080::HDC1080Component, esphome::he60r::HE60rCover, esphome::heatpumpir::HeatpumpIRClimate, esphome::hlw8012::HLW8012Component, esphome::hm3301::HM3301Component, esphome::hmc5883l::HMC5883LComponent, esphome::homeassistant::HomeassistantBinarySensor, esphome::homeassistant::HomeassistantNumber, esphome::homeassistant::HomeassistantSensor, esphome::homeassistant::HomeassistantSwitch, esphome::homeassistant::HomeassistantTextSensor, esphome::homeassistant::HomeassistantTime, esphome::honeywellabp::HONEYWELLABPSensor, esphome::hte501::HTE501Component, esphome::http_request::HttpRequestUpdate, esphome::http_request::OtaHttpRequestComponent, esphome::htu21d::HTU21DComponent, esphome::htu31d::HTU31DComponent, esphome::hx711::HX711Sensor, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::i2c::ArduinoI2CBus, esphome::i2c::IDFI2CBus, esphome::i2s_audio::I2SAudioComponent, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::i2s_audio::I2SAudioMicrophone, esphome::i2s_audio::I2SAudioSpeaker, esphome::iaqcore::IAQCore, esphome::ili9xxx::ILI9XXXDisplay, esphome::improv_serial::ImprovSerialComponent, esphome::ina219::INA219Component, esphome::ina226::INA226Component, esphome::ina260::INA260Component, esphome::ina2xx_base::INA2XX, esphome::ina2xx_i2c::INA2XXI2C, esphome::ina2xx_spi::INA2XXSPI, esphome::ina3221::INA3221Component, esphome::inkplate6::Inkplate6, esphome::integration::IntegrationSensor, esphome::internal_temperature::InternalTemperatureSensor, esphome::interval::IntervalTrigger, esphome::kmeteriso::KMeterISOComponent, esphome::lc709203f::Lc709203f, esphome::lcd_base::LCDDisplay, esphome::lcd_gpio::GPIOLCDDisplay, esphome::lcd_menu::LCDCharacterMenuComponent, esphome::lcd_pcf8574::PCF8574LCDDisplay, esphome::ld2420::LD2420Component, esphome::ledc::LEDCOutput, esphome::libretiny_pwm::LibreTinyPWM, esphome::light::LightState, esphome::lightwaverf::LightWaveRF, esphome::lilygo_t5_47::LilygoT547Touchscreen, esphome::logger::LoggerLevelSelect, esphome::lps22::LPS22Component, esphome::ltr390::LTR390Component, esphome::ltr501::LTRAlsPs501Component, esphome::ltr_als_ps::LTRAlsPsComponent, esphome::lvgl::LvglComponent, esphome::lvgl::LVGLNumber, esphome::lvgl::LVGLSelect, esphome::lvgl::LVGLSwitch, esphome::m5stack_8angle::M5Stack8AngleComponent, esphome::m5stack_8angle::M5Stack8AngleLightOutput, esphome::matrix_keypad::MatrixKeypad, esphome::max17043::MAX17043Component, esphome::max31855::MAX31855Sensor, esphome::max31856::MAX31856Sensor, esphome::max31865::MAX31865Sensor, esphome::max44009::MAX44009Sensor, esphome::max6675::MAX6675Sensor, esphome::max6956::MAX6956, esphome::max6956::MAX6956LedChannel, esphome::max7219::MAX7219Component, esphome::max7219digit::MAX7219Component, esphome::max9611::MAX9611Component, esphome::mcp23008::MCP23008, esphome::mcp23016::MCP23016, esphome::mcp23017::MCP23017, esphome::mcp23s08::MCP23S08, esphome::mcp23s17::MCP23S17, esphome::mcp3008::MCP3008, esphome::mcp3204::MCP3204, esphome::mcp4461::Mcp4461Component, esphome::mcp4725::MCP4725, esphome::mcp4728::MCP4728Component, esphome::mcp9600::MCP9600Component, esphome::mcp9808::MCP9808Sensor, esphome::mdns::MDNSComponent, esphome::mhz19::MHZ19Component, esphome::micro_wake_word::MicroWakeWord, esphome::micronova::MicroNova, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::mipi_spi::MipiSpi, esphome::mixer_speaker::MixerSpeaker, esphome::mixer_speaker::SourceSpeaker, esphome::mlx90393::MLX90393Cls, esphome::mlx90614::MLX90614Component, esphome::mmc5603::MMC5603Component, esphome::mmc5983::MMC5983Component, esphome::modbus::Modbus, esphome::modbus_controller::ModbusController, esphome::modbus_controller::ModbusSwitch, esphome::mpl3115a2::MPL3115A2Component, esphome::mpr121::MPR121Component, esphome::mpu6050::MPU6050Component, esphome::mpu6886::MPU6886Component, esphome::mqtt::MQTTAlarmControlPanelComponent, esphome::mqtt::MQTTBinarySensorComponent, esphome::mqtt::MQTTButtonComponent, esphome::mqtt::MQTTClientComponent, esphome::mqtt::MQTTClimateComponent, esphome::mqtt::MQTTCoverComponent, esphome::mqtt::MQTTDateComponent, esphome::mqtt::MQTTDateTimeComponent, esphome::mqtt::MQTTEventComponent, esphome::mqtt::MQTTFanComponent, esphome::mqtt::MQTTJSONLightComponent, esphome::mqtt::MQTTLockComponent, esphome::mqtt::MQTTMessageTrigger, esphome::mqtt::MQTTNumberComponent, esphome::mqtt::MQTTSelectComponent, esphome::mqtt::MQTTSensorComponent, esphome::mqtt::MQTTSwitchComponent, esphome::mqtt::MQTTTextComponent, esphome::mqtt::MQTTTextSensor, esphome::mqtt::MQTTTimeComponent, esphome::mqtt::MQTTUpdateComponent, esphome::mqtt::MQTTValveComponent, esphome::mqtt_subscribe::MQTTSubscribeSensor, esphome::mqtt_subscribe::MQTTSubscribeTextSensor, esphome::ms5611::MS5611Component, esphome::ms8607::MS8607Component, esphome::msa3xx::MSA3xxComponent, esphome::my9231::MY9231OutputComponent, esphome::nau7802::NAU7802Sensor, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, T_COLOR_FEATURE >, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, NeoRgbFeature >, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, NeoRgbwFeature >, esphome::nextion::Nextion, esphome::nfc::NfcTagBinarySensor, esphome::noblex::NoblexClimate, esphome::npi19::NPI19Component, esphome::ntc::NTC, esphome::number::ValueRangeTrigger, esphome::opentherm::OpenthermHub, esphome::opentherm::OpenthermNumber, esphome::opentherm::OpenthermSwitch, esphome::openthread::OpenThreadComponent, esphome::openthread::OpenThreadSrpComponent, esphome::output::OutputSwitch, esphome::packet_transport::PacketTransport, esphome::pca6416a::PCA6416AComponent, esphome::pca9554::PCA9554Component, esphome::pca9685::PCA9685Output, esphome::pcd8544::PCD8544, esphome::pcf85063::PCF85063Component, esphome::pcf8563::PCF8563Component, esphome::pcf8574::PCF8574Component, esphome::pi4ioe5v6408::PI4IOE5V6408Component, esphome::pid::PIDClimate, esphome::pid::PIDClimateSensor, esphome::pid::PIDSimulator, esphome::pm1006::PM1006Component, esphome::pm2005::PM2005Component, esphome::pmsa003i::PMSA003IComponent, esphome::pn532::PN532, esphome::pn532_spi::PN532Spi, esphome::pn7150::PN7150, esphome::pn7160::PN7160, esphome::pn7160_spi::PN7160Spi, esphome::power_supply::PowerSupply, esphome::preferences::IntervalSyncer, esphome::ProjectUpdateTrigger, esphome::prometheus::PrometheusHandler, esphome::pulse_counter::PulseCounterSensor, esphome::pulse_meter::PulseMeterSensor, esphome::pulse_width::PulseWidthSensor, esphome::pylontech::PylontechComponent, esphome::pzem004t::PZEM004T, esphome::qmc5883l::QMC5883LComponent, esphome::qmp6988::QMP6988Component, esphome::qspi_dbi::QspiDbi, esphome::qwiic_pir::QwiicPIRComponent, esphome::rc522::RC522, esphome::rc522_spi::RC522Spi, esphome::remote_receiver::RemoteReceiverComponent, esphome::remote_transmitter::RemoteTransmitterComponent, esphome::resampler::ResamplerSpeaker, esphome::resistance::ResistanceSensor, esphome::rotary_encoder::RotaryEncoderSensor, esphome::rp2040_pio_led_strip::RP2040PIOLEDStripLightOutput, esphome::rp2040_pwm::RP2040PWM, esphome::rpi_dpi_rgb::RpiDpiRgb, esphome::scd30::SCD30Component, esphome::scd4x::SCD4XComponent, esphome::sdl::Sdl, esphome::sdl::SdlTouchscreen, esphome::sdp3x::SDP3XComponent, esphome::sds011::SDS011Component, esphome::seeed_mr24hpc1::MR24HPC1Component, esphome::seeed_mr60fda2::MR60FDA2Component, esphome::sen0321_sensor::Sen0321Sensor, esphome::sen5x::SEN5XComponent, esphome::sensor::HeartbeatFilter, esphome::sensor::ThrottleAverageFilter, esphome::sensor::ValueRangeTrigger, esphome::servo::Servo, esphome::sfa30::SFA30Component, esphome::sgp30::SGP30Component, esphome::sgp4x::SGP4xComponent, esphome::shelly_dimmer::ShellyDimmer, esphome::sht3xd::SHT3XDComponent, esphome::sht4x::SHT4XComponent, esphome::shtcx::SHTCXComponent, esphome::sigma_delta_output::SigmaDeltaOutput, esphome::slow_pwm::SlowPWMOutput, esphome::sm10bit_base::Sm10BitBase, esphome::sm16716::SM16716, esphome::sm2135::SM2135, esphome::sm2235::SM2235, esphome::sm2335::SM2335, esphome::sn74hc165::SN74HC165Component, esphome::sn74hc595::SN74HC595Component, esphome::sn74hc595::SN74HC595GPIOComponent, esphome::sn74hc595::SN74HC595SPIComponent, esphome::sntp::SNTPComponent, esphome::sonoff_d1::SonoffD1Output, esphome::sound_level::SoundLevelComponent, esphome::speaker::SpeakerMediaPlayer, esphome::speed::SpeedFan, esphome::spi::SPIComponent, esphome::spi_device::SPIDeviceComponent, esphome::spi_led_strip::SpiLedStrip, esphome::sprinkler::Sprinkler, esphome::sprinkler::SprinklerControllerNumber, esphome::sprinkler::SprinklerControllerSwitch, esphome::sps30::SPS30Component, esphome::ssd1306_base::SSD1306, esphome::ssd1306_i2c::I2CSSD1306, esphome::ssd1306_spi::SPISSD1306, esphome::ssd1322_base::SSD1322, esphome::ssd1322_spi::SPISSD1322, esphome::ssd1325_base::SSD1325, esphome::ssd1325_spi::SPISSD1325, esphome::ssd1327_base::SSD1327, esphome::ssd1327_i2c::I2CSSD1327, esphome::ssd1327_spi::SPISSD1327, esphome::ssd1331_base::SSD1331, esphome::ssd1331_spi::SPISSD1331, esphome::ssd1351_base::SSD1351, esphome::ssd1351_spi::SPISSD1351, esphome::st7567_base::ST7567, esphome::st7567_i2c::I2CST7567, esphome::st7567_spi::SPIST7567, esphome::st7701s::ST7701S, esphome::st7735::ST7735, esphome::st7789v::ST7789V, esphome::st7920::ST7920, esphome::StartupTrigger, esphome::statsd::StatsdComponent, esphome::status::StatusBinarySensor, esphome::status_led::StatusLEDLightOutput, esphome::sts3x::STS3XComponent, esphome::sun_gtil2::SunGTIL2, esphome::switch_::SwitchBinarySensor, esphome::sx126x::SX126x, esphome::sx126x::SX126xTransport, esphome::sx127x::SX127x, esphome::sx127x::SX127xTransport, esphome::sx1509::SX1509Component, esphome::sx1509::SX1509FloatOutputChannel, esphome::syslog::Syslog, esphome::tc74::TC74Component, esphome::tca9548a::TCA9548AComponent, esphome::tca9555::TCA9555Component, esphome::tcs34725::TCS34725Component, esphome::tee501::TEE501Component, esphome::teleinfo::TeleInfo, esphome::tem3200::TEM3200Component, esphome::template_::TemplateAlarmControlPanel, esphome::template_::TemplateBinarySensor, esphome::template_::TemplateCover, esphome::template_::TemplateDate, esphome::template_::TemplateDateTime, esphome::template_::TemplateFan, esphome::template_::TemplateNumber, esphome::template_::TemplateSelect, esphome::template_::TemplateSwitch, esphome::template_::TemplateText, esphome::template_::TemplateTime, esphome::template_::TemplateValve, esphome::thermostat::ThermostatClimate, esphome::time_based::TimeBasedCover, esphome::tlc59208f::TLC59208FOutput, esphome::tlc5947::TLC5947, esphome::tlc5971::TLC5971, esphome::tm1621::TM1621Display, esphome::tm1637::TM1637Display, esphome::tm1638::TM1638Component, esphome::tm1651::TM1651Display, esphome::tmp1075::TMP1075Sensor, esphome::tmp117::TMP117Component, esphome::tof10120::TOF10120Sensor, esphome::tormatic::Tormatic, esphome::toshiba::ToshibaClimate, esphome::total_daily_energy::TotalDailyEnergy, esphome::touchscreen::TouchscreenBinarySensor, esphome::tsl2561::TSL2561Sensor, esphome::tsl2591::TSL2591Component, esphome::tt21100::TT21100Button, esphome::tt21100::TT21100Touchscreen, esphome::ttp229_bsf::TTP229BSFComponent, esphome::ttp229_lsf::TTP229LSFComponent, esphome::tuya::Tuya, esphome::tuya::TuyaBinarySensor, esphome::tuya::TuyaClimate, esphome::tuya::TuyaCover, esphome::tuya::TuyaFan, esphome::tuya::TuyaLight, esphome::tuya::TuyaNumber, esphome::tuya::TuyaSelect, esphome::tuya::TuyaSensor, esphome::tuya::TuyaSwitch, esphome::tuya::TuyaTextSensor, esphome::tx20::Tx20Component, esphome::uart::ESP32ArduinoUARTComponent, esphome::uart::ESP8266UartComponent, esphome::uart::HostUartComponent, esphome::uart::IDFUARTComponent, esphome::uart::LibreTinyUARTComponent, esphome::uart::RP2040UartComponent, esphome::udp::UDPComponent, esphome::udp::UDPTransport, esphome::ufire_ec::UFireECComponent, esphome::ufire_ise::UFireISEComponent, esphome::uln2003::ULN2003, esphome::ultrasonic::UltrasonicSensorComponent, esphome::uponor_smatrix::UponorSmatrixComponent, esphome::uptime::UptimeTextSensor, esphome::uptime::UptimeTimestampSensor, esphome::usb_host::USBClient, esphome::usb_host::USBHost, esphome::usb_uart::USBUartComponent, esphome::veml3235::VEML3235Sensor, esphome::veml7700::VEML7700Component, esphome::version::VersionTextSensor, esphome::vl53l0x::VL53L0XSensor, esphome::voice_assistant::VoiceAssistant, esphome::wake_on_lan::WakeOnLanButton, esphome::waveshare_epaper::WaveshareEPaper2P13InV3, esphome::waveshare_epaper::WaveshareEPaper7C, esphome::waveshare_epaper::WaveshareEPaperBase, esphome::web_server::WebServer, esphome::web_server::WebServerOTAComponent, esphome::weikai_i2c::WeikaiComponentI2C, esphome::weikai_spi::WeikaiComponentSPI, esphome::whirlpool::WhirlpoolClimate, esphome::wiegand::Wiegand, esphome::wifi::WiFiComponent, esphome::wifi_info::MacAddressWifiInfo, esphome::wireguard::Wireguard, esphome::wl_134::Wl134Component, esphome::x9c::X9cOutput, esphome::xgzp68xx::XGZP68XXComponent, esphome::xl9535::XL9535Component, esphome::xpt2046::XPT2046Component, esphome::yashima::YashimaClimate, esphome::zhlt01::ZHLT01Climate, and esphome::zyaura::ZyAuraSensor.
Definition at line 81 of file component.cpp.
bool esphome::Component::should_warn_of_blocking | ( | uint32_t | blocking_time | ) |
Definition at line 180 of file component.cpp.
void esphome::Component::status_clear_error | ( | ) |
Definition at line 309 of file component.cpp.
void esphome::Component::status_clear_warning | ( | ) |
Definition at line 303 of file component.cpp.
bool esphome::Component::status_has_error | ( | ) | const |
Definition at line 272 of file component.cpp.
bool esphome::Component::status_has_warning | ( | ) | const |
Definition at line 271 of file component.cpp.
void esphome::Component::status_momentary_error | ( | const std::string & | name, |
uint32_t | length = 5000 ) |
Definition at line 319 of file component.cpp.
void esphome::Component::status_momentary_warning | ( | const std::string & | name, |
uint32_t | length = 5000 ) |
Definition at line 315 of file component.cpp.
void esphome::Component::status_set_error | ( | const char * | message = "unspecified" | ) |
Definition at line 281 of file component.cpp.
void esphome::Component::status_set_warning | ( | const char * | message = "unspecified" | ) |
Definition at line 273 of file component.cpp.
|
inlinevirtual |
Called during teardown to allow component to gracefully finish operations.
Reimplemented in esphome::api::APIServer.
Definition at line 118 of file component.h.
|
protected |
Definition at line 405 of file component.h.
|
protected |
State of this component - each bit has a purpose: Bits 0-1: Component state (0x00=CONSTRUCTION, 0x01=SETUP, 0x02=LOOP, 0x03=FAILED) Bit 2: STATUS_LED_WARNING Bit 3: STATUS_LED_ERROR Bits 4-7: Unused - reserved for future expansion (50% of the bits are free)
Definition at line 412 of file component.h.
|
protected |
ISR-safe flag for enable_loop_soon_any_context.
Definition at line 413 of file component.h.
|
protected |
Warn if blocked for this many ms (max 65.5s)
Definition at line 406 of file component.h.