ESPHome
2023.11.6
|
#include <component.h>
Public Member Functions | |
virtual void | setup () |
Where the component's initialization should happen. More... | |
virtual void | loop () |
This method will be called repeatedly. More... | |
virtual void | dump_config () |
virtual float | get_setup_priority () const |
priority of setup(). More... | |
float | get_actual_setup_priority () const |
void | set_setup_priority (float priority) |
virtual float | get_loop_priority () const |
priority of loop(). More... | |
void | call () |
virtual void | on_shutdown () |
virtual void | on_safe_shutdown () |
uint32_t | get_component_state () const |
virtual void | mark_failed () |
Mark this component as failed. More... | |
bool | is_failed () |
bool | is_ready () |
virtual bool | can_proceed () |
bool | status_has_warning () |
bool | status_has_error () |
void | status_set_warning () |
void | status_set_error () |
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. More... | |
const char * | get_component_source () const |
Get the integration where this component was declared as a string. More... | |
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. More... | |
void | set_interval (uint32_t interval, std::function< void()> &&f) |
bool | cancel_interval (const std::string &name) |
Cancel an interval function. More... | |
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. More... | |
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. More... | |
void | set_timeout (const std::string &name, uint32_t timeout, std::function< void()> &&f) |
Set a timeout function with a unique name. More... | |
void | set_timeout (uint32_t timeout, std::function< void()> &&f) |
bool | cancel_timeout (const std::string &name) |
Cancel a timeout function. More... | |
void | defer (const std::string &name, std::function< void()> &&f) |
Defer a callback to the next loop() call. More... | |
void | defer (std::function< void()> &&f) |
Defer a callback to the next loop() call. More... | |
bool | cancel_defer (const std::string &name) |
Cancel a defer callback using the specified name, name must not be empty. More... | |
Protected Attributes | |
uint32_t | component_state_ {0x0000} |
State of this component. More... | |
float | setup_priority_override_ {NAN} |
const char * | component_source_ {nullptr} |
Definition at line 67 of file component.h.
void esphome::Component::call | ( | ) |
Definition at line 81 of file component.cpp.
|
protectedvirtual |
Reimplemented in esphome::mqtt::MQTTComponent.
Definition at line 78 of file component.cpp.
|
protectedvirtual |
Reimplemented in esphome::mqtt::MQTTComponent.
Definition at line 76 of file component.cpp.
|
protectedvirtual |
Reimplemented in esphome::PollingComponent, esphome::light::AddressableLight, esphome::mqtt::MQTTComponent, and esphome::time::RealTimeClock.
Definition at line 77 of file component.cpp.
|
virtual |
Reimplemented in esphome::mqtt::MQTTClientComponent, esphome::wifi::WiFiComponent, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::ethernet::EthernetComponent, esphome::esp32_ble_server::BLEServer, and esphome::wireguard::Wireguard.
Definition at line 142 of file component.cpp.
|
protected |
Cancel a defer callback using the specified name, name must not be empty.
Definition at line 121 of file component.cpp.
|
protected |
Cancel an interval function.
name | The identifier for this interval function. |
Definition at line 55 of file component.cpp.
|
protected |
Cancel a retry function.
name | The identifier for this retry function. |
Definition at line 64 of file component.cpp.
|
protected |
Cancel a timeout function.
name | The identifier for this timeout function. |
Definition at line 72 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 124 of file component.cpp.
|
protected |
Defer a callback to the next loop() call.
Definition at line 118 of file component.cpp.
|
virtual |
Reimplemented in esphome::nextion::Nextion, esphome::waveshare_epaper::WaveshareEPaper2P13InDKE, esphome::waveshare_epaper::WaveshareEPaper7P5InHDB, esphome::waveshare_epaper::WaveshareEPaper7P5InV2alt, esphome::waveshare_epaper::WaveshareEPaper7P5InV2, esphome::waveshare_epaper::WaveshareEPaper7P5InBC, esphome::waveshare_epaper::WaveshareEPaper7P5InBV3, esphome::modbus_controller::ModbusController, esphome::waveshare_epaper::WaveshareEPaper7P5InBV2, esphome::waveshare_epaper::WaveshareEPaper7P5In, esphome::waveshare_epaper::WaveshareEPaper5P8InV2, esphome::spi::SPIComponent, esphome::mqtt::MQTTMessageTrigger, esphome::waveshare_epaper::WaveshareEPaper5P8In, esphome::waveshare_epaper::WaveshareEPaper4P2InBV2, esphome::tsl2591::TSL2591Component, esphome::waveshare_epaper::WaveshareEPaper4P2In, esphome::wifi::WiFiComponent, esphome::mqtt::MQTTClientComponent, esphome::waveshare_epaper::WaveshareEPaper2P9InB, esphome::fastled_base::FastLEDLightOutput, esphome::sprinkler::Sprinkler, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::remote_base::RemoteReceiverBinarySensorBase, esphome::waveshare_epaper::GDEW0154M09, esphome::vbus::VBusCustomSensor, esphome::waveshare_epaper::GDEY029T94, esphome::esp32_camera::ESP32Camera, esphome::graph::Graph, esphome::waveshare_epaper::WaveshareEPaper2P7In, esphome::st7789v::ST7789V, esphome::micronova::MicroNova, esphome::vbus::DeltaSolCSPlusSensor, esphome::sprinkler::SprinklerControllerSwitch, esphome::wifi_info::MacAddressWifiInfo, esphome::bedjet::BedJetHub, esphome::vbus::VBusCustomBSensor, esphome::ld2420::LD2420Component, esphome::web_server::WebServer, esphome::wifi_info::BSSIDWiFiInfo, esphome::sprinkler::SprinklerControllerNumber, esphome::emc2101::Emc2101Component, esphome::inkplate6::Inkplate6, esphome::vbus::DeltaSolCS2Sensor, esphome::bme680::BME680Component, esphome::ble_presence::BLEPresenceDevice, esphome::vbus::DeltaSolCSPlusBSensor, esphome::logger::Logger, esphome::deep_sleep::DeepSleepComponent, esphome::fingerprint_grow::FingerprintGrowComponent, esphome::wifi_info::SSIDWiFiInfo, esphome::mpl3115a2::MPL3115A2Component, esphome::waveshare_epaper::WaveshareEPaperTypeA, esphome::ble_rssi::BLERSSISensor, esphome::dfplayer::DFPlayer, esphome::esp32_ble::ESP32BLE, esphome::qmp6988::QMP6988Component, esphome::tuya::Tuya, esphome::havells_solar::HavellsSolar, esphome::rotary_encoder::RotaryEncoderSensor, esphome::vbus::DeltaSolCS2BSensor, esphome::cs5460a::CS5460AComponent, esphome::as7341::AS7341Component, esphome::ade7953_base::ADE7953, esphome::bme280::BME280Component, esphome::max31856::MAX31856Sensor, esphome::pulse_counter::PulseCounterSensor, esphome::rp2040_pio_led_strip::RP2040PIOLEDStripLightOutput, esphome::sgp4x::SGP4xComponent, esphome::bmp3xx::BMP3XXComponent, esphome::wifi_info::ScanResultsWiFiInfo, esphome::bl0939::BL0939, esphome::bl0940::BL0940, esphome::mpr121::MPR121Component, esphome::vbus::DeltaSolCSensor, esphome::dsmr::Dsmr, esphome::sen21231_sensor::Sen21231Sensor, esphome::zyaura::ZyAuraSensor, esphome::canbus::Canbus, esphome::daly_bms::DalyBmsComponent, esphome::template_::TemplateText, esphome::tsl2561::TSL2561Sensor, esphome::bmp280::BMP280Component, esphome::bmp581::BMP581Component, esphome::ota::OTAComponent, esphome::vbus::DeltaSolCBSensor, esphome::tmp1075::TMP1075Sensor, esphome::esp32_rmt_led_strip::ESP32RMTLEDStripLightOutput, esphome::sdm_meter::SDMMeter, esphome::thermostat::ThermostatClimate, esphome::bme680_bsec::BME680BSECComponent, esphome::ltr390::LTR390Component, esphome::modbus_controller::ModbusBinaryOutput, esphome::tcs34725::TCS34725Component, esphome::max6956::MAX6956, esphome::sim800l::Sim800LComponent, esphome::sonoff_d1::SonoffD1Output, esphome::grove_tb6612fng::GroveMotorDriveTB6612FNG, esphome::esp32_touch::ESP32TouchComponent, esphome::sen5x::SEN5XComponent, esphome::uart::ESP8266UartComponent, esphome::bluetooth_proxy::BluetoothProxy, esphome::ac_dimmer::AcDimmer, esphome::ble_client::BLEClient, esphome::light::LightState, esphome::mopeka_std_check::MopekaStdCheck, esphome::rf_bridge::RFBridgeComponent, esphome::ruuvitag::RuuviTag, esphome::cd74hc4067::CD74HC4067Sensor, esphome::cap1188::CAP1188Component, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::ethernet::EthernetComponent, esphome::mcp4728::MCP4728Component, esphome::wifi_info::DNSAddressWifiInfo, esphome::dht::DHT, esphome::ili9xxx::ILI9XXXDisplay, esphome::spi_led_strip::SpiLedStrip, esphome::ads1115::ADS1115Component, esphome::pca9685::PCA9685Output, esphome::tlc59208f::TLC59208FOutput, esphome::xpt2046::XPT2046Component, esphome::sm2135::SM2135, esphome::vbus::DeltaSolBS2009BSensor, esphome::alpha3::Alpha3, esphome::bl0942::BL0942, esphome::improv_serial::ImprovSerialComponent, esphome::pcd8544::PCD8544, esphome::selec_meter::SelecMeter, esphome::dps310::DPS310Component, esphome::st7735::ST7735, esphome::vbus::DeltaSolBS2009Sensor, esphome::esp32_ble_beacon::ESP32BLEBeacon, esphome::hmc5883l::HMC5883LComponent, esphome::http_request::HttpRequestComponent, esphome::esp32_ble_server::BLEServer, esphome::max9611::MAX9611Component, esphome::modbus_controller::ModbusSelect, esphome::pvvx_mithermometer::PVVXDisplay, esphome::ezo::EZOSensor, esphome::haier::HonClimate, esphome::max7219digit::MAX7219Component, esphome::qwiic_pir::QwiicPIRComponent, esphome::adc::ADCSensor, esphome::climate_ir::ClimateIR, esphome::dac7678::DAC7678Output, esphome::mqtt::MQTTSensorComponent, esphome::tx20::Tx20Component, esphome::ufire_ise::UFireISEComponent, esphome::wl_134::Wl134Component, esphome::max31865::MAX31865Sensor, esphome::rtttl::Rtttl, esphome::servo::Servo, esphome::template_::TemplateCover, esphome::wiegand::Wiegand, esphome::binary_sensor_map::BinarySensorMap, esphome::pmsx003::PMSX003Component, esphome::sx1509::SX1509Component, esphome::template_::TemplateAlarmControlPanel, esphome::esp32_improv::ESP32ImprovComponent, esphome::haier::HaierClimateBase, esphome::mcp3008::MCP3008Sensor, esphome::modbus_controller::ModbusBinarySensor, esphome::mopeka_pro_check::MopekaProCheck, esphome::pulse_width::PulseWidthSensor, esphome::sgp30::SGP30Component, esphome::sun::SunTextSensor, esphome::wireguard::Wireguard, esphome::hlw8012::HLW8012Component, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::lcd_gpio::GPIOLCDDisplay, esphome::pmsa003i::PMSA003IComponent, esphome::mqtt::MQTTFanComponent, esphome::qmc5883l::QMC5883LComponent, esphome::sigma_delta_output::SigmaDeltaOutput, esphome::ufire_ec::UFireECComponent, esphome::vl53l0x::VL53L0XSensor, esphome::ble_scanner::BLEScanner, esphome::modbus_controller::ModbusSwitch, esphome::pulse_meter::PulseMeterSensor, esphome::teleinfo::TeleInfo, esphome::vbus::VBus, esphome::cse7761::CSE7761Component, esphome::lcd_menu::LCDCharacterMenuComponent, esphome::modbus_controller::ModbusTextSensor, esphome::mqtt::MQTTCoverComponent, esphome::power_supply::PowerSupply, esphome::status_led::StatusLEDLightOutput, esphome::tm1637::TM1637Display, esphome::integration::IntegrationSensor, esphome::mdns::MDNSComponent, esphome::pca9554::PCA9554Component, esphome::pn532::PN532, esphome::t6615::T6615Component, esphome::tt21100::TT21100Touchscreen, esphome::anova::Anova, esphome::api::APIServer, esphome::esp32_camera_web_server::CameraWebServer, esphome::modbus_controller::ModbusNumber, esphome::pid::PIDClimateSensor, esphome::pzemac::PZEMAC, esphome::scd30::SCD30Component, esphome::sm10bit_base::Sm10BitBase, esphome::sps30::SPS30Component, esphome::tca9548a::TCA9548AComponent, esphome::xl9535::XL9535Component, esphome::atc_mithermometer::ATCMiThermometer, esphome::ledc::LEDCOutput, esphome::lightwaverf::LightWaveRF, esphome::modbus_controller::ModbusSensor, esphome::pcf8574::PCF8574Component, esphome::pvvx_mithermometer::PVVXMiThermometer, esphome::resistance::ResistanceSensor, esphome::sen0321_sensor::Sen0321Sensor, esphome::tlc5947::TLC5947, esphome::tm1638::TM1638Component, esphome::ttp229_bsf::TTP229BSFComponent, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::ble_client::BLESensor, esphome::bp1658cj::BP1658CJ, esphome::ccs811::CCS811Component, esphome::duty_cycle::DutyCycleSensor, esphome::mqtt::MQTTNumberComponent, esphome::mqtt::MQTTSelectComponent, esphome::mqtt::MQTTTextComponent, esphome::rp2040_pwm::RP2040PWM, esphome::st7920::ST7920, esphome::ektf2232::EKTF2232Touchscreen, esphome::esp8266_pwm::ESP8266PWM, esphome::ezo_pmp::EzoPMP, esphome::growatt_solar::GrowattSolar, esphome::hbridge::HBridgeFan, esphome::hm3301::HM3301Component, esphome::hx711::HX711Sensor, esphome::kuntze::Kuntze, esphome::lilygo_t5_47::LilygoT547Touchscreen, esphome::matrix_keypad::MatrixKeypad, esphome::midea::ac::AirConditioner, esphome::modbus_controller::ModbusFloatOutput, esphome::pca6416a::PCA6416AComponent, esphome::radon_eye_rd200::RadonEyeRD200, esphome::shelly_dimmer::ShellyDimmer, esphome::sml::Sml, esphome::total_daily_energy::TotalDailyEnergy, esphome::ttp229_lsf::TTP229LSFComponent, esphome::uln2003::ULN2003, esphome::xiaomi_miscale::XiaomiMiscale, esphome::xiaomi_rtcgq02lm::XiaomiRTCGQ02LM, esphome::am43::Am43Component, esphome::am43::Am43, esphome::bang_bang::BangBangClimate, esphome::ethernet_info::IPAddressEthernetInfo, esphome::mcp9600::MCP9600Component, esphome::my9231::MY9231OutputComponent, esphome::pzemdc::PZEMDC, esphome::rc522_spi::RC522Spi, esphome::scd4x::SCD4XComponent, esphome::ultrasonic::UltrasonicSensorComponent, esphome::debug::DebugComponent, esphome::libretiny_pwm::LibreTinyPWM, esphome::max7219::MAX7219Component, esphome::mqtt::MQTTBinarySensorComponent, esphome::pzem004t::PZEM004T, esphome::sm300d2::SM300D2Sensor, esphome::sn74hc595::SN74HC595Component, esphome::xiaomi_cgpr1::XiaomiCGPR1, esphome::xiaomi_mjyd02yla::XiaomiMJYD02YLA, esphome::bh1750::BH1750Sensor, esphome::ble_client::BLETextSensor, esphome::honeywellabp2_i2c::HONEYWELLABP2Sensor, esphome::mqtt::MQTTJSONLightComponent, esphome::mqtt::MQTTTextSensor, esphome::sht4x::SHT4XComponent, esphome::sm16716::SM16716, esphome::tm1651::TM1651Display, esphome::uart::UARTSwitch, esphome::xiaomi_wx08zm::XiaomiWX08ZM, esphome::adc128s102::ADC128S102Sensor, esphome::bedjet::BedJetClimate, esphome::duty_time_sensor::DutyTimeSensor, esphome::gpio::GPIOSwitch, esphome::honeywellabp::HONEYWELLABPSensor, esphome::i2c::ArduinoI2CBus, esphome::i2c::IDFI2CBus, esphome::libretiny::LTComponent, esphome::mcp3204::MCP3204Sensor, esphome::modbus::Modbus, esphome::mqtt::MQTTButtonComponent, esphome::mqtt::MQTTLockComponent, esphome::mqtt::MQTTSwitchComponent, esphome::slow_pwm::SlowPWMOutput, esphome::wifi_info::IPAddressWiFiInfo, esphome::xiaomi_mue4094rt::XiaomiMUE4094RT, esphome::ade7953_spi::AdE7953Spi, esphome::airthings_wave_mini::AirthingsWaveMini, esphome::airthings_wave_plus::AirthingsWavePlus, esphome::ble_client::BLEClientRSSISensor, esphome::bp5758d::BP5758D, esphome::captive_portal::CaptivePortal, esphome::cse7766::CSE7766Component, esphome::dallas::DallasComponent, esphome::fs3000::FS3000Component, esphome::max31855::MAX31855Sensor, esphome::mcp3008::MCP3008, esphome::qr_code::QrCode, esphome::sds011::SDS011Component, esphome::tm1621::TM1621Display, esphome::uart::RP2040UartComponent, esphome::xiaomi_cgg1::XiaomiCGG1, esphome::as3935_spi::SPIAS3935Component, esphome::bedjet::BedJetFan, esphome::bmp085::BMP085Component, esphome::custom::CustomBinarySensorConstructor, esphome::custom::CustomTextSensorConstructor, esphome::ee895::EE895Component, esphome::esp32_dac::ESP32DAC, esphome::gpio::GPIOBinaryOutput, esphome::htu21d::HTU21DComponent, esphome::mcp3204::MCP3204, esphome::mhz19::MHZ19Component, esphome::mmc5603::MMC5603Component, esphome::mqtt_subscribe::MQTTSubscribeSensor, esphome::mqtt_subscribe::MQTTSubscribeTextSensor, esphome::pid::PIDClimate, esphome::rc522::RC522, esphome::sht3xd::SHT3XDComponent, esphome::shtcx::SHTCXComponent, esphome::sn74hc165::SN74HC165Component, esphome::sun::SunSensor, esphome::tuya::TuyaCover, esphome::tuya::TuyaLight, esphome::uart::ESP32ArduinoUARTComponent, esphome::xiaomi_cgd1::XiaomiCGD1, esphome::xiaomi_cgdk2::XiaomiCGDK2, esphome::xiaomi_gcls002::XiaomiGCLS002, esphome::xiaomi_hhccjcy01::XiaomiHHCCJCY01, esphome::xiaomi_hhccpot002::XiaomiHHCCPOT002, esphome::xiaomi_jqjcy01ym::XiaomiJQJCY01YM, esphome::xiaomi_lywsd02::XiaomiLYWSD02, esphome::xiaomi_lywsd03mmc::XiaomiLYWSD03MMC, esphome::xiaomi_lywsdcgq::XiaomiLYWSDCGQ, esphome::xiaomi_mhoc303::XiaomiMHOC303, esphome::xiaomi_mhoc401::XiaomiMHOC401, esphome::a01nyub::A01nyubComponent, esphome::b_parasite::BParasite, esphome::ble_client::BLEClientSwitch, esphome::feedback::FeedbackCover, esphome::hte501::HTE501Component, esphome::inkbird_ibsth1_mini::InkbirdIbstH1Mini, esphome::max44009::MAX44009Sensor, esphome::mcp23s08::MCP23S08, esphome::mcp23s17::MCP23S17, esphome::pn532_spi::PN532Spi, esphome::sdp3x::SDP3XComponent, esphome::sntp::SNTPComponent, esphome::ssd1306_spi::SPISSD1306, esphome::ssd1322_spi::SPISSD1322, esphome::ssd1325_spi::SPISSD1325, esphome::ssd1327_spi::SPISSD1327, esphome::ssd1331_spi::SPISSD1331, esphome::ssd1351_spi::SPISSD1351, esphome::template_::TemplateTextSensor, esphome::x9c::X9cOutput, esphome::xgzp68xx::XGZP68XXComponent, esphome::adc128s102::ADC128S102, esphome::ble_client::BLEBinaryOutput, esphome::custom::CustomSensorConstructor, esphome::custom::CustomSwitchConstructor, esphome::gp8403::GP8403, esphome::gpio::GPIOBinarySensor, esphome::hdc1080::HDC1080Component, esphome::iaqcore::IAQCore, esphome::pmwcs3::PMWCS3Component, esphome::senseair::SenseAirComponent, esphome::template_::TemplateNumber, esphome::template_::TemplateSelect, esphome::tt21100::TT21100Button, esphome::uart::LibreTinyUARTComponent, esphome::a4988::A4988, esphome::ade7953_i2c::AdE7953I2c, esphome::current_based::CurrentBasedCover, esphome::hrxl_maxsonar_wr::HrxlMaxsonarWrComponent, esphome::kalman_combinator::KalmanCombinatorComponent, esphome::max6675::MAX6675Sensor, esphome::max6956::MAX6956LedChannel, esphome::mcp23008::MCP23008, esphome::mcp23017::MCP23017, esphome::mlx90393::MLX90393Cls, esphome::ntc::NTC, esphome::output::OutputSwitch, esphome::pm1006::PM1006Component, esphome::sfa30::SFA30Component, esphome::smt100::SMT100Component, esphome::sts3x::STS3XComponent, esphome::sx1509::SX1509FloatOutputChannel, esphome::uart::UARTButton, esphome::wake_on_lan::WakeOnLanButton, esphome::zio_ultrasonic::ZioUltrasonicComponent, esphome::atm90e26::ATM90E26Component, esphome::atm90e32::ATM90E32Component, esphome::cd74hc4067::CD74HC4067Component, esphome::ct_clamp::CTClampSensor, esphome::emc2101::EMC2101Sensor, esphome::endstop::EndstopCover, esphome::haier::Smartair2Climate, esphome::hyt271::HYT271Component, esphome::ina219::INA219Component, esphome::mcp4725::MCP4725, esphome::output::OutputLock, esphome::pipsolar::PipsolarSwitch, esphome::sm2235::SM2235, esphome::sm2335::SM2335, esphome::speed::SpeedFan, esphome::template_::TemplateBinarySensor, esphome::template_::TemplateSensor, esphome::template_::TemplateSwitch, esphome::tuya::TuyaSelect, esphome::uart::IDFUARTComponent, esphome::aht10::AHT10Component, esphome::as3935_i2c::I2CAS3935Component, esphome::ds1307::DS1307Component, esphome::ens210::ENS210Component, esphome::homeassistant::HomeassistantBinarySensor, esphome::homeassistant::HomeassistantSensor, esphome::homeassistant::HomeassistantTextSensor, esphome::homeassistant::HomeassistantTime, esphome::key_collector::KeyCollector, esphome::lcd_pcf8574::PCF8574LCDDisplay, esphome::mmc5983::MMC5983Component, esphome::pcf85063::PCF85063Component, esphome::pcf8563::PCF8563Component, esphome::pn532_i2c::PN532I2C, esphome::sml::SmlTextSensor, esphome::spi_device::SPIDeviceComponent, esphome::status::StatusBinarySensor, esphome::status_led::StatusLED, esphome::tee501::TEE501Component, esphome::template_::TemplateLock, esphome::time_based::TimeBasedCover, esphome::tmp102::TMP102Component, esphome::tof10120::TOF10120Sensor, esphome::tuya::TuyaClimate, esphome::tuya::TuyaFan, esphome::wifi_signal::WiFiSignalSensor, esphome::am2320::AM2320Component, esphome::binary::BinaryFan, esphome::bmi160::BMI160Component, 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::dht12::DHT12Component, esphome::esp32_hall::ESP32HallSensor, esphome::gcja5::GCJA5Component, esphome::gp8403::GP8403Output, esphome::ina226::INA226Component, esphome::ina260::INA260Component, esphome::ina3221::INA3221Component, esphome::mcp9808::MCP9808Sensor, esphome::micronova::MicroNovaButton, esphome::micronova::MicroNovaSwitch, esphome::mlx90614::MLX90614Component, esphome::mpu6050::MPU6050Component, esphome::mpu6886::MPU6886Component, esphome::ms5611::MS5611Component, esphome::ssd1306_i2c::I2CSSD1306, esphome::ssd1327_i2c::I2CSSD1327, esphome::tmp117::TMP117Component, esphome::tuya::TuyaBinarySensor, esphome::tuya::TuyaNumber, esphome::tuya::TuyaSensor, esphome::tuya::TuyaSwitch, esphome::tuya::TuyaTextSensor, esphome::version::VersionTextSensor, esphome::analog_threshold::AnalogThresholdBinarySensor, esphome::copy::CopyButton, esphome::mcp47a1::MCP47A1, esphome::output::OutputButton, esphome::rc522_i2c::RC522I2C, esphome::safe_mode::SafeModeButton, esphome::safe_mode::SafeModeSwitch, esphome::sml::SmlSensor, esphome::teleinfo::TeleInfoSensor, esphome::tm1638::TM1638OutputLed, esphome::tm1638::TM1638SwitchLed, esphome::uptime::UptimeSensor, esphome::factory_reset::FactoryResetButton, esphome::factory_reset::FactoryResetSwitch, esphome::internal_temperature::InternalTemperatureSensor, esphome::ld2420::LD2420BinarySensor, esphome::ld2420::LD2420Sensor, esphome::ld2420::LD2420TextSensor, esphome::restart::RestartButton, esphome::restart::RestartSwitch, esphome::shutdown::ShutdownButton, esphome::shutdown::ShutdownSwitch, esphome::vbus::DeltaSolBSPlusBSensor, esphome::vbus::DeltaSolBSPlusSensor, and esphome::teleinfo::TeleInfoTextSensor.
Definition at line 163 of file component.cpp.
float esphome::Component::get_actual_setup_priority | ( | ) | const |
Definition at line 164 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 107 of file component.cpp.
uint32_t esphome::Component::get_component_state | ( | ) | const |
Definition at line 80 of file component.cpp.
|
virtual |
priority of loop().
higher -> executed earlier
Defaults to 0.
Reimplemented in esphome::wifi::WiFiComponent, esphome::deep_sleep::DeepSleepComponent, esphome::status_led::StatusLEDLightOutput, esphome::pca9554::PCA9554Component, and esphome::status_led::StatusLED.
Definition at line 43 of file component.cpp.
|
virtual |
priority of setup().
higher -> executed earlier
Defaults to 0.
Reimplemented in esphome::nextion::Nextion, esphome::sensor::HeartbeatFilter, esphome::sensor::DebounceFilter, esphome::mqtt::MQTTMessageTrigger, esphome::spi::SPIComponent, esphome::sensor::TimeoutFilter, esphome::WaitUntilAction< Ts >, esphome::tsl2591::TSL2591Component, esphome::script::ScriptWaitAction< C, Ts >, esphome::sensor::ThrottleAverageFilter, esphome::wifi::WiFiComponent, esphome::mqtt::MQTTClientComponent, esphome::fastled_base::FastLEDLightOutput, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::ld2420::LD2420Component, esphome::esp32_camera::ESP32Camera, esphome::graph::Graph, esphome::DelayAction< Ts >, esphome::sprinkler::SprinklerControllerSwitch, esphome::st7789v::ST7789V, esphome::LoopTrigger, esphome::bedjet::BedJetHub, esphome::ShutdownTrigger, esphome::web_server::WebServer, esphome::wifi_info::BSSIDWiFiInfo, esphome::sprinkler::SprinklerControllerNumber, esphome::StartupTrigger, esphome::web_server_base::WebServerBase, esphome::binary_sensor::MultiClickTrigger, esphome::emc2101::Emc2101Component, esphome::bme680::BME680Component, esphome::logger::Logger, esphome::ble_presence::BLEPresenceDevice, esphome::inkplate6::Inkplate6, esphome::mqtt::MQTTComponent, esphome::deep_sleep::DeepSleepComponent, esphome::mpl3115a2::MPL3115A2Component, esphome::binary_sensor::AutorepeatFilter, esphome::ble_rssi::BLERSSISensor, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, T_COLOR_FEATURE >, esphome::wifi_info::SSIDWiFiInfo, esphome::esp32_ble::ESP32BLE, esphome::qmp6988::QMP6988Component, esphome::rotary_encoder::RotaryEncoderSensor, esphome::ForCondition< Ts >, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::as7341::AS7341Component, esphome::tuya::Tuya, esphome::bme280::BME280Component, esphome::cs5460a::CS5460AComponent, esphome::max31856::MAX31856Sensor, esphome::pulse_counter::PulseCounterSensor, esphome::sgp4x::SGP4xComponent, esphome::bmp3xx::BMP3XXComponent, esphome::mpr121::MPR121Component, esphome::wifi_info::ScanResultsWiFiInfo, esphome::daly_bms::DalyBmsComponent, esphome::zyaura::ZyAuraSensor, esphome::canbus::Canbus, esphome::tsl2561::TSL2561Sensor, esphome::template_::TemplateText, esphome::bmp280::BMP280Component, esphome::ota::OTAComponent, esphome::bmp581::BMP581Component, esphome::tmp1075::TMP1075Sensor, esphome::binary_sensor::DelayedOffFilter, esphome::bme680_bsec::BME680BSECComponent, esphome::number::ValueRangeTrigger, esphome::sonoff_d1::SonoffD1Output, esphome::voice_assistant::VoiceAssistant, esphome::esp32_touch::ESP32TouchComponent, esphome::ltr390::LTR390Component, esphome::tcs34725::TCS34725Component, esphome::prometheus::PrometheusHandler, esphome::uart::ESP8266UartComponent, esphome::light::LightState, esphome::rp2040_pio_led_strip::RP2040PIOLEDStripLightOutput, esphome::cd74hc4067::CD74HC4067Sensor, esphome::mopeka_std_check::MopekaStdCheck, esphome::ruuvitag::RuuviTag, esphome::sen5x::SEN5XComponent, esphome::sensor::ValueRangeTrigger, esphome::dht::DHT, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::max6956::MAX6956, esphome::ssd1306_base::SSD1306, esphome::st7735::ST7735, esphome::binary_sensor::DelayedOnFilter, esphome::cap1188::CAP1188Component, esphome::ethernet::EthernetComponent, esphome::mcp4728::MCP4728Component, esphome::ads1115::ADS1115Component, esphome::pca9685::PCA9685Output, esphome::sm2135::SM2135, esphome::tlc59208f::TLC59208FOutput, esphome::xpt2046::XPT2046Component, esphome::globals::RestoringGlobalsComponent< T >, esphome::improv_serial::ImprovSerialComponent, esphome::wifi_info::DNSAddressWifiInfo, esphome::alpha3::Alpha3, esphome::dps310::DPS310Component, esphome::hbridge::HBridgeLightOutput, esphome::i2s_audio::I2SAudioSpeaker, esphome::max7219digit::MAX7219Component, esphome::esp32_ble_beacon::ESP32BLEBeacon, esphome::hmc5883l::HMC5883LComponent, esphome::http_request::HttpRequestComponent, esphome::pvvx_mithermometer::PVVXDisplay, esphome::esp32_ble_server::BLEServer, esphome::ezo::EZOSensor, esphome::gps::GPS, esphome::max9611::MAX9611Component, esphome::esp32_improv::ESP32ImprovComponent, esphome::adc::ADCSensor, esphome::qwiic_pir::QwiicPIRComponent, esphome::dac7678::DAC7678Output, esphome::template_::TemplateCover, esphome::tx20::Tx20Component, esphome::wireguard::Wireguard, esphome::max31865::MAX31865Sensor, esphome::mcp23016::MCP23016, esphome::pcd8544::PCD8544, esphome::servo::Servo, esphome::sx1509::SX1509Component, esphome::binary_sensor::DelayedOnOffFilter, esphome::haier::HaierClimateBase, esphome::mcp3008::MCP3008Sensor, esphome::mopeka_pro_check::MopekaProCheck, esphome::pmsa003i::PMSA003IComponent, esphome::pulse_width::PulseWidthSensor, esphome::sgp30::SGP30Component, esphome::ssd1325_base::SSD1325, esphome::tm1637::TM1637Display, esphome::hlw8012::HLW8012Component, esphome::mdns::MDNSComponent, esphome::pmsx003::PMSX003Component, esphome::e131::E131Component, esphome::qmc5883l::QMC5883LComponent, esphome::tm1621::TM1621Display, esphome::vbus::VBus, esphome::vl53l0x::VL53L0XSensor, esphome::wiegand::Wiegand, esphome::ble_scanner::BLEScanner, esphome::pn532::PN532, esphome::power_supply::PowerSupply, esphome::status_led::StatusLEDLightOutput, esphome::cse7761::CSE7761Component, esphome::esp32_rmt_led_strip::ESP32RMTLEDStripLightOutput, esphome::ssd1351_base::SSD1351, esphome::time::CronTrigger, esphome::integration::IntegrationSensor, esphome::modbus_controller::ModbusNumber, esphome::pulse_meter::PulseMeterSensor, esphome::ssd1322_base::SSD1322, esphome::ssd1327_base::SSD1327, esphome::tt21100::TT21100Touchscreen, esphome::anova::Anova, esphome::display_menu_base::DisplayMenuComponent, esphome::esp32_camera_web_server::CameraWebServer, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::ledc::LEDCOutput, esphome::scd30::SCD30Component, esphome::sps30::SPS30Component, esphome::tca9548a::TCA9548AComponent, esphome::tlc5947::TLC5947, esphome::tm1638::TM1638Component, esphome::xl9535::XL9535Component, esphome::atc_mithermometer::ATCMiThermometer, esphome::bp1658cj::BP1658CJ, esphome::ccs811::CCS811Component, esphome::esp32_ble_client::BLEClientBase, esphome::htu21d::HTU21DComponent, esphome::ili9xxx::ILI9XXXDisplay, esphome::lcd_menu::LCDCharacterMenuComponent, esphome::pvvx_mithermometer::PVVXMiThermometer, esphome::resistance::ResistanceSensor, esphome::rp2040_pwm::RP2040PWM, esphome::ttp229_bsf::TTP229BSFComponent, esphome::ultrasonic::UltrasonicSensorComponent, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::ble_client::BLESensor, esphome::captive_portal::CaptivePortal, esphome::esp8266_pwm::ESP8266PWM, esphome::max7219::MAX7219Component, esphome::mcp9600::MCP9600Component, esphome::st7920::ST7920, esphome::api::APIServer, esphome::ezo_pmp::EzoPMP, esphome::hm3301::HM3301Component, esphome::hx711::HX711Sensor, esphome::my9231::MY9231OutputComponent, esphome::total_daily_energy::TotalDailyEnergy, esphome::ttp229_lsf::TTP229LSFComponent, esphome::uln2003::ULN2003, esphome::xiaomi_miscale::XiaomiMiscale, esphome::xiaomi_rtcgq02lm::XiaomiRTCGQ02LM, esphome::am43::Am43Component, esphome::am43::Am43, esphome::duty_cycle::DutyCycleSensor, esphome::libretiny_pwm::LibreTinyPWM, esphome::modbus::Modbus, esphome::pca9554::PCA9554Component, esphome::pcf8574::PCF8574Component, esphome::sm10bit_base::Sm10BitBase, esphome::sntp::SNTPComponent, esphome::ssd1331_base::SSD1331, esphome::t6615::T6615Component, esphome::bh1750::BH1750Sensor, esphome::i2c::ArduinoI2CBus, esphome::i2c::IDFI2CBus, esphome::lcd_base::LCDDisplay, esphome::rdm6300::RDM6300Component, esphome::sm16716::SM16716, esphome::template_::TemplateSwitch, esphome::xiaomi_cgpr1::XiaomiCGPR1, esphome::xiaomi_mjyd02yla::XiaomiMJYD02YLA, esphome::ble_client::BLETextSensor, esphome::pca6416a::PCA6416AComponent, esphome::sds011::SDS011Component, esphome::slow_pwm::SlowPWMOutput, esphome::template_::TemplateLock, esphome::xiaomi_wx08zm::XiaomiWX08ZM, esphome::adc128s102::ADC128S102Sensor, esphome::bedjet::BedJetClimate, esphome::ble_client::BLEClientSwitch, esphome::bp5758d::BP5758D, esphome::debug::DebugComponent, esphome::duty_time_sensor::DutyTimeSensor, esphome::ethernet_info::IPAddressEthernetInfo, esphome::mcp3204::MCP3204Sensor, esphome::rc522::RC522, esphome::scd4x::SCD4XComponent, esphome::sn74hc595::SN74HC595Component, esphome::xiaomi_mue4094rt::XiaomiMUE4094RT, esphome::ble_client::BLEClientRSSISensor, esphome::bmp085::BMP085Component, esphome::dallas::DallasComponent, esphome::esp32_dac::ESP32DAC, esphome::fs3000::FS3000Component, esphome::hdc1080::HDC1080Component, esphome::honeywellabp2_i2c::HONEYWELLABP2Sensor, esphome::max31855::MAX31855Sensor, esphome::mcp3008::MCP3008, esphome::shelly_dimmer::ShellyDimmer, esphome::uart::RP2040UartComponent, esphome::xiaomi_cgg1::XiaomiCGG1, esphome::bedjet::BedJetFan, esphome::gpio::GPIOBinaryOutput, esphome::honeywellabp::HONEYWELLABPSensor, esphome::kmeteriso::KMeterISOComponent, esphome::libretiny::LTComponent, esphome::mcp3204::MCP3204, esphome::mmc5603::MMC5603Component, esphome::mqtt_subscribe::MQTTSubscribeSensor, esphome::mqtt_subscribe::MQTTSubscribeTextSensor, esphome::pm1006::PM1006Component, esphome::sdp3x::SDP3XComponent, esphome::sht3xd::SHT3XDComponent, esphome::sht4x::SHT4XComponent, esphome::shtcx::SHTCXComponent, esphome::smt100::SMT100Component, esphome::uart::ESP32ArduinoUARTComponent, esphome::xiaomi_cgd1::XiaomiCGD1, esphome::xiaomi_cgdk2::XiaomiCGDK2, esphome::xiaomi_gcls002::XiaomiGCLS002, esphome::xiaomi_hhccjcy01::XiaomiHHCCJCY01, esphome::xiaomi_hhccpot002::XiaomiHHCCPOT002, esphome::xiaomi_jqjcy01ym::XiaomiJQJCY01YM, esphome::xiaomi_lywsd02::XiaomiLYWSD02, esphome::xiaomi_lywsd03mmc::XiaomiLYWSD03MMC, esphome::xiaomi_lywsdcgq::XiaomiLYWSDCGQ, esphome::xiaomi_mhoc303::XiaomiMHOC303, esphome::xiaomi_mhoc401::XiaomiMHOC401, esphome::b_parasite::BParasite, esphome::ble_client::BLEBinaryOutput, esphome::emc2101::EMC2101Sensor, esphome::feedback::FeedbackCover, esphome::gpio::GPIOBinarySensor, esphome::hyt271::HYT271Component, esphome::iaqcore::IAQCore, esphome::inkbird_ibsth1_mini::InkbirdIbstH1Mini, esphome::max44009::MAX44009Sensor, esphome::mcp23xxx_base::MCP23XXXBase, esphome::wifi_info::IPAddressWiFiInfo, esphome::a4988::A4988, esphome::adc128s102::ADC128S102, esphome::cse7766::CSE7766Component, esphome::gp8403::GP8403, esphome::gpio::GPIOSwitch, esphome::pmwcs3::PMWCS3Component, esphome::sn74hc165::SN74HC165Component, esphome::template_::TemplateNumber, esphome::template_::TemplateSelect, esphome::tmp102::TMP102Component, esphome::uart::LibreTinyUARTComponent, esphome::bmi160::BMI160Component, esphome::current_based::CurrentBasedCover, esphome::ee895::EE895Component, esphome::max6675::MAX6675Sensor, esphome::max6956::MAX6956LedChannel, esphome::mlx90393::MLX90393Cls, esphome::mpu6050::MPU6050Component, esphome::mpu6886::MPU6886Component, esphome::ntc::NTC, esphome::sts3x::STS3XComponent, esphome::sx1509::SX1509FloatOutputChannel, esphome::template_::TemplateBinarySensor, esphome::template_::TemplateSensor, esphome::wifi_signal::WiFiSignalSensor, esphome::atm90e26::ATM90E26Component, esphome::atm90e32::ATM90E32Component, esphome::cd74hc4067::CD74HC4067Component, esphome::ct_clamp::CTClampSensor, esphome::endstop::EndstopCover, esphome::homeassistant::HomeassistantTime, esphome::hte501::HTE501Component, esphome::ina219::INA219Component, esphome::ina260::INA260Component, esphome::preferences::IntervalSyncer, esphome::spi_device::SPIDeviceComponent, esphome::status::StatusBinarySensor, esphome::status_led::StatusLED, esphome::template_::TemplateTextSensor, esphome::uart::IDFUARTComponent, esphome::waveshare_epaper::WaveshareEPaper, esphome::aht10::AHT10Component, esphome::analog_threshold::AnalogThresholdBinarySensor, esphome::ds1307::DS1307Component, esphome::gcja5::GCJA5Component, esphome::homeassistant::HomeassistantBinarySensor, esphome::homeassistant::HomeassistantSensor, esphome::homeassistant::HomeassistantTextSensor, esphome::ina3221::INA3221Component, esphome::mhz19::MHZ19Component, esphome::mlx90614::MLX90614Component, esphome::mmc5983::MMC5983Component, esphome::output::OutputSwitch, esphome::pcf85063::PCF85063Component, esphome::pcf8563::PCF8563Component, esphome::tee501::TEE501Component, esphome::time_based::TimeBasedCover, esphome::tof10120::TOF10120Sensor, esphome::am2320::AM2320Component, 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::dht12::DHT12Component, esphome::gp8403::GP8403Output, esphome::ina226::INA226Component, esphome::kalman_combinator::KalmanCombinatorComponent, esphome::mcp9808::MCP9808Sensor, esphome::ms5611::MS5611Component, esphome::output::OutputLock, esphome::sfa30::SFA30Component, esphome::tmp117::TMP117Component, esphome::uptime::UptimeSensor, esphome::version::VersionTextSensor, esphome::zio_ultrasonic::ZioUltrasonicComponent, esphome::copy::CopyButton, esphome::ens210::ENS210Component, esphome::senseair::SenseAirComponent, esphome::interval::IntervalTrigger, and esphome::sm300d2::SM300D2Sensor.
Definition at line 45 of file component.cpp.
bool esphome::Component::has_overridden_loop | ( | ) | const |
Definition at line 171 of file component.cpp.
bool esphome::Component::is_failed | ( | ) |
Definition at line 137 of file component.cpp.
bool esphome::Component::is_ready | ( | ) |
Definition at line 138 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::nextion::Nextion, esphome::modbus_controller::ModbusController, esphome::WaitUntilAction< Ts >, esphome::wifi::WiFiComponent, esphome::script::ScriptWaitAction< C, Ts >, esphome::mqtt::MQTTClientComponent, esphome::sprinkler::Sprinkler, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::esp32_camera::ESP32Camera, esphome::sprinkler::SprinklerControllerSwitch, esphome::micronova::MicroNova, esphome::LoopTrigger, esphome::bedjet::BedJetHub, esphome::script::QueueingScript< Ts >, esphome::ld2420::LD2420Component, esphome::web_server::WebServer, esphome::deep_sleep::DeepSleepComponent, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::esp32_ble::ESP32BLE, esphome::rotary_encoder::RotaryEncoderSensor, esphome::tuya::Tuya, esphome::ForCondition< Ts >, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::cs5460a::CS5460AComponent, esphome::mpr121::MPR121Component, esphome::uart::UARTDummyReceiver, esphome::bl0939::BL0939, esphome::bl0940::BL0940, esphome::canbus::Canbus, esphome::daly_bms::DalyBmsComponent, esphome::ota::OTAComponent, esphome::bme680_bsec::BME680BSECComponent, esphome::tm1637::TM1637Display, esphome::dsmr::Dsmr, esphome::voice_assistant::VoiceAssistant, esphome::esp32_touch::ESP32TouchComponent, esphome::sim800l::Sim800LComponent, esphome::sonoff_d1::SonoffD1Output, esphome::xpt2046::XPT2046Component, esphome::bluetooth_proxy::BluetoothProxy, esphome::ble_client::BLEClient, esphome::light::LightState, esphome::cap1188::CAP1188Component, esphome::mcp4728::MCP4728Component, esphome::rf_bridge::RFBridgeComponent, esphome::sm2135::SM2135, esphome::tm1638::TM1638Component, esphome::globals::RestoringGlobalsComponent< T >, esphome::pca9685::PCA9685Output, esphome::tlc59208f::TLC59208FOutput, esphome::ethernet::EthernetComponent, esphome::i2s_audio::I2SAudioSpeaker, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::slow_pwm::SlowPWMOutput, esphome::binary_sensor_map::BinarySensorMap, esphome::gps::GPS, esphome::improv_serial::ImprovSerialComponent, esphome::bl0942::BL0942, esphome::esp32_ble_server::BLEServer, esphome::rtttl::Rtttl, esphome::tx20::Tx20Component, esphome::ezo::EZOSensor, esphome::max7219digit::MAX7219Component, esphome::sx1509::SX1509Component, esphome::template_::TemplateAlarmControlPanel, esphome::qwiic_pir::QwiicPIRComponent, esphome::vl53l0x::VL53L0XSensor, esphome::wl_134::Wl134Component, esphome::esp32_improv::ESP32ImprovComponent, esphome::template_::TemplateCover, esphome::wiegand::Wiegand, esphome::pn532::PN532, esphome::pmsx003::PMSX003Component, esphome::e131::E131Component, esphome::esp32_camera_web_server::CameraWebServer, esphome::haier::HaierClimateBase, esphome::mdns::MDNSComponent, esphome::tlc5947::TLC5947, esphome::vbus::VBus, esphome::wireguard::Wireguard, esphome::bp1658cj::BP1658CJ, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::time::CronTrigger, esphome::pulse_meter::PulseMeterSensor, esphome::sm10bit_base::Sm10BitBase, esphome::ttp229_bsf::TTP229BSFComponent, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::dfplayer::DFPlayer, esphome::ezo_pmp::EzoPMP, esphome::my9231::MY9231OutputComponent, esphome::sntp::SNTPComponent, esphome::teleinfo::TeleInfo, esphome::tt21100::TT21100Touchscreen, esphome::api::APIServer, esphome::esp32_ble_client::BLEClientBase, esphome::sm16716::SM16716, esphome::t6615::T6615Component, esphome::total_daily_energy::TotalDailyEnergy, esphome::ttp229_lsf::TTP229LSFComponent, esphome::bp5758d::BP5758D, esphome::anova::Anova, esphome::ektf2232::EKTF2232Touchscreen, esphome::lilygo_t5_47::LilygoT547Touchscreen, esphome::matrix_keypad::MatrixKeypad, esphome::rc522::RC522, esphome::sml::Sml, esphome::uart::UARTDebugger, esphome::uln2003::ULN2003, esphome::ble_client::BLESensor, esphome::captive_portal::CaptivePortal, esphome::growatt_solar::GrowattSolar, esphome::status_led::StatusLEDLightOutput, esphome::template_::TemplateSwitch, esphome::am43::Am43Component, esphome::gpio::GPIOBinarySensor, esphome::sds011::SDS011Component, esphome::template_::TemplateLock, esphome::debug::DebugComponent, esphome::duty_time_sensor::DutyTimeSensor, esphome::kuntze::Kuntze, esphome::bedjet::BedJetClimate, esphome::ble_client::BLEClientSwitch, esphome::honeywellabp2_i2c::HONEYWELLABP2Sensor, esphome::i2s_audio::I2SAudioMicrophone, esphome::modbus::Modbus, esphome::pzem004t::PZEM004T, esphome::rdm6300::RDM6300Component, esphome::ble_client::BLEBinaryOutput, esphome::ble_client::BLEClientRSSISensor, esphome::ble_client::BLETextSensor, esphome::a01nyub::A01nyubComponent, esphome::a4988::A4988, esphome::cse7766::CSE7766Component, esphome::feedback::FeedbackCover, esphome::pca9554::PCA9554Component, esphome::pm1006::PM1006Component, esphome::servo::Servo, esphome::smt100::SMT100Component, esphome::sn74hc165::SN74HC165Component, esphome::current_based::CurrentBasedCover, esphome::hrxl_maxsonar_wr::HrxlMaxsonarWrComponent, esphome::status_led::StatusLED, esphome::uart::UARTSwitch, esphome::ct_clamp::CTClampSensor, esphome::endstop::EndstopCover, esphome::gcja5::GCJA5Component, esphome::template_::TemplateBinarySensor, esphome::key_collector::KeyCollector, esphome::time_based::TimeBasedCover, esphome::tuya::TuyaClimate, and esphome::status::StatusBinarySensor.
Definition at line 49 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 112 of file component.cpp.
|
inlinevirtual |
Reimplemented in esphome::ota::OTAComponent, and esphome::waveshare_epaper::WaveshareEPaper.
Definition at line 108 of file component.h.
|
inlinevirtual |
Reimplemented in esphome::mqtt::MQTTClientComponent, esphome::ShutdownTrigger, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::esp32_touch::ESP32TouchComponent, esphome::ethernet::EthernetComponent, esphome::globals::RestoringGlobalsComponent< T >, esphome::mdns::MDNSComponent, esphome::pn532::PN532, esphome::wireguard::Wireguard, esphome::power_supply::PowerSupply, esphome::api::APIServer, esphome::esp32_camera_web_server::CameraWebServer, and esphome::preferences::IntervalSyncer.
Definition at line 107 of file component.h.
|
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 148 of file component.h.
|
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: 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 interval function. |
interval | The interval in ms. |
f | The function (or lambda) that should be called |
Definition at line 51 of file component.cpp.
|
protected |
Definition at line 130 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 multipling 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 59 of file component.cpp.
|
protected |
Definition at line 133 of file component.cpp.
void esphome::Component::set_setup_priority | ( | float | priority | ) |
Definition at line 169 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 68 of file component.cpp.
|
protected |
Definition at line 127 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::nextion::Nextion, esphome::modbus_controller::ModbusController, esphome::sensor::HeartbeatFilter, esphome::spi::SPIComponent, esphome::mqtt::MQTTMessageTrigger, esphome::tsl2591::TSL2591Component, esphome::sensor::ThrottleAverageFilter, esphome::wifi::WiFiComponent, esphome::mqtt::MQTTClientComponent, esphome::fastled_base::FastLEDLightOutput, esphome::sprinkler::Sprinkler, esphome::esp32_ble_tracker::ESP32BLETracker, esphome::zhlt01::ZHLT01Climate, esphome::canbus::CanbusTrigger, esphome::esp32_camera::ESP32Camera, esphome::graph::Graph, esphome::st7789v::ST7789V, esphome::micronova::MicroNova, esphome::sprinkler::SprinklerControllerSwitch, esphome::wifi_info::MacAddressWifiInfo, esphome::bedjet::BedJetHub, esphome::ld2420::LD2420Component, esphome::inkplate6::Inkplate6, esphome::web_server::WebServer, esphome::StartupTrigger, esphome::sprinkler::SprinklerControllerNumber, esphome::bme680::BME680Component, esphome::emc2101::Emc2101Component, esphome::binary_sensor::MultiClickTrigger, esphome::heatpumpir::HeatpumpIRClimate, esphome::deep_sleep::DeepSleepComponent, esphome::fingerprint_grow::FingerprintGrowComponent, esphome::mpl3115a2::MPL3115A2Component, esphome::sn74hc595::SN74HC595SPIComponent, esphome::qmp6988::QMP6988Component, esphome::esp32_ble::ESP32BLE, esphome::tuya::Tuya, esphome::globals::RestoringGlobalStringComponent< T, SZ >, esphome::rotary_encoder::RotaryEncoderSensor, esphome::midea::ApplianceBase< T >, esphome::midea::ApplianceBase< dudanov::midea::ac::AirConditioner >, esphome::as7341::AS7341Component, esphome::bme280::BME280Component, esphome::cs5460a::CS5460AComponent, esphome::max31856::MAX31856Sensor, esphome::ade7953_base::ADE7953, esphome::pulse_counter::PulseCounterSensor, esphome::bmp3xx::BMP3XXComponent, esphome::neopixelbus::NeoPixelBusLightOutputBase< T_METHOD, T_COLOR_FEATURE >, esphome::bl0939::BL0939, esphome::bl0940::BL0940, esphome::mpr121::MPR121Component, esphome::sgp4x::SGP4xComponent, esphome::sn74hc595::SN74HC595GPIOComponent, esphome::zyaura::ZyAuraSensor, esphome::bmp581::BMP581Component, esphome::canbus::Canbus, esphome::tsl2561::TSL2561Sensor, esphome::bmp280::BMP280Component, esphome::pid::PIDSimulator, esphome::template_::TemplateText, esphome::ota::OTAComponent, esphome::thermostat::ThermostatClimate, esphome::bme680_bsec::BME680BSECComponent, esphome::tmp1075::TMP1075Sensor, esphome::number::ValueRangeTrigger, esphome::ltr390::LTR390Component, esphome::dsmr::Dsmr, esphome::tcs34725::TCS34725Component, esphome::voice_assistant::VoiceAssistant, esphome::grove_tb6612fng::GroveMotorDriveTB6612FNG, esphome::sonoff_d1::SonoffD1Output, esphome::esp32_touch::ESP32TouchComponent, esphome::sen5x::SEN5XComponent, esphome::uart::ESP8266UartComponent, esphome::rp2040_pio_led_strip::RP2040PIOLEDStripLightOutput, esphome::ble_client::BLEClient, esphome::pcd8544::PCD8544, esphome::prometheus::PrometheusHandler, esphome::ac_dimmer::AcDimmer, esphome::light::LightState, esphome::cap1188::CAP1188Component, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::ili9xxx::ILI9XXXDisplay, esphome::mcp4728::MCP4728Component, esphome::dht::DHT, esphome::ethernet::EthernetComponent, esphome::i2s_audio::I2SAudioSpeaker, esphome::ads1115::ADS1115Component, esphome::pca9685::PCA9685Output, esphome::tlc59208f::TLC59208FOutput, esphome::xpt2046::XPT2046Component, esphome::max6956::MAX6956, esphome::st7735::ST7735, esphome::addressable_light::AddressableLightDisplay, esphome::bl0942::BL0942, esphome::sensor::ValueRangeTrigger, esphome::sm2135::SM2135, esphome::dps310::DPS310Component, esphome::improv_serial::ImprovSerialComponent, esphome::esp32_ble_beacon::ESP32BLEBeacon, esphome::hmc5883l::HMC5883LComponent, esphome::alpha3::Alpha3, esphome::globals::RestoringGlobalsComponent< T >, esphome::max9611::MAX9611Component, esphome::esp32_ble_server::BLEServer, esphome::adc::ADCSensor, esphome::climate_ir::ClimateIR, esphome::dac7678::DAC7678Output, esphome::esp32_improv::ESP32ImprovComponent, esphome::template_::TemplateAlarmControlPanel, esphome::tx20::Tx20Component, esphome::max31865::MAX31865Sensor, esphome::max7219digit::MAX7219Component, esphome::mqtt::MQTTSensorComponent, esphome::qwiic_pir::QwiicPIRComponent, esphome::ufire_ise::UFireISEComponent, esphome::wl_134::Wl134Component, esphome::sx1509::SX1509Component, esphome::template_::TemplateCover, esphome::wiegand::Wiegand, esphome::pulse_width::PulseWidthSensor, esphome::hlw8012::HLW8012Component, esphome::mcp3008::MCP3008Sensor, esphome::pmsa003i::PMSA003IComponent, esphome::sgp30::SGP30Component, esphome::waveshare_epaper::WaveshareEPaper, esphome::e131::E131Component, esphome::haier::HaierClimateBase, esphome::mcp23016::MCP23016, esphome::qmc5883l::QMC5883LComponent, esphome::sigma_delta_output::SigmaDeltaOutput, esphome::wireguard::Wireguard, esphome::mqtt::MQTTFanComponent, esphome::toshiba::ToshibaClimate, esphome::ufire_ec::UFireECComponent, esphome::vl53l0x::VL53L0XSensor, esphome::cse7761::CSE7761Component, esphome::esp32_rmt_led_strip::ESP32RMTLEDStripLightOutput, esphome::modbus_controller::ModbusSwitch, esphome::power_supply::PowerSupply, esphome::teleinfo::TeleInfo, esphome::i2s_audio::I2SAudioMediaPlayer, esphome::integration::IntegrationSensor, esphome::mdns::MDNSComponent, esphome::pulse_meter::PulseMeterSensor, esphome::sen0321_sensor::Sen0321Sensor, esphome::ssd1306_base::SSD1306, esphome::status_led::StatusLEDLightOutput, esphome::tm1637::TM1637Display, esphome::whirlpool::WhirlpoolClimate, esphome::hbridge::HBridgeLightOutput, esphome::lcd_menu::LCDCharacterMenuComponent, esphome::pn532::PN532, esphome::sm10bit_base::Sm10BitBase, esphome::tca9548a::TCA9548AComponent, esphome::tt21100::TT21100Touchscreen, esphome::xl9535::XL9535Component, esphome::esp32_ble_client::BLEClientBase, esphome::esp32_camera_web_server::CameraWebServer, esphome::ledc::LEDCOutput, esphome::lightwaverf::LightWaveRF, esphome::scd30::SCD30Component, esphome::sps30::SPS30Component, esphome::tm1638::TM1638Component, esphome::ttp229_bsf::TTP229BSFComponent, esphome::absolute_humidity::AbsoluteHumidityComponent, esphome::mqtt::MQTTNumberComponent, esphome::mqtt::MQTTSelectComponent, esphome::mqtt::MQTTTextComponent, esphome::rp2040_pwm::RP2040PWM, esphome::st7920::ST7920, esphome::tlc5947::TLC5947, esphome::api::APIServer, esphome::bp1658cj::BP1658CJ, esphome::duty_cycle::DutyCycleSensor, esphome::esp8266_pwm::ESP8266PWM, esphome::hbridge::HBridgeFan, esphome::hm3301::HM3301Component, esphome::hx711::HX711Sensor, esphome::pid::PIDClimateSensor, esphome::servo::Servo, esphome::total_daily_energy::TotalDailyEnergy, esphome::ttp229_lsf::TTP229LSFComponent, esphome::anova::Anova, esphome::bang_bang::BangBangClimate, esphome::ektf2232::EKTF2232Touchscreen, esphome::lcd_base::LCDDisplay, esphome::lilygo_t5_47::LilygoT547Touchscreen, esphome::matrix_keypad::MatrixKeypad, esphome::mcp9600::MCP9600Component, esphome::my9231::MY9231OutputComponent, esphome::scd4x::SCD4XComponent, esphome::shelly_dimmer::ShellyDimmer, esphome::uln2003::ULN2003, esphome::ultrasonic::UltrasonicSensorComponent, esphome::ccs811::CCS811Component, esphome::libretiny_pwm::LibreTinyPWM, esphome::rc522_spi::RC522Spi, esphome::resistance::ResistanceSensor, esphome::bh1750::BH1750Sensor, esphome::globals::GlobalsComponent< T >, esphome::max7219::MAX7219Component, esphome::mqtt::MQTTBinarySensorComponent, esphome::sht4x::SHT4XComponent, esphome::sn74hc595::SN74HC595Component, esphome::tm1651::TM1651Display, esphome::am43::Am43Component, esphome::am43::Am43, esphome::gpio::GPIOSwitch, esphome::i2c::ArduinoI2CBus, esphome::i2c::IDFI2CBus, esphome::i2s_audio::I2SAudioComponent, esphome::mqtt::MQTTButtonComponent, esphome::mqtt::MQTTClimateComponent, esphome::mqtt::MQTTJSONLightComponent, esphome::mqtt::MQTTLockComponent, esphome::mqtt::MQTTSwitchComponent, esphome::mqtt::MQTTTextSensor, esphome::noblex::NoblexClimate, esphome::slow_pwm::SlowPWMOutput, esphome::sm16716::SM16716, esphome::ssd1325_base::SSD1325, esphome::captive_portal::CaptivePortal, esphome::dallas::DallasComponent, esphome::demo::DemoCover, esphome::kmeteriso::KMeterISOComponent, esphome::max31855::MAX31855Sensor, esphome::mcp3008::MCP3008, esphome::sds011::SDS011Component, esphome::uart::RP2040UartComponent, esphome::ade7953_spi::AdE7953Spi, esphome::as3935_spi::SPIAS3935Component, esphome::bedjet::BedJetClimate, esphome::bmp085::BMP085Component, esphome::bp5758d::BP5758D, esphome::demo::DemoClimate, esphome::demo::DemoNumber, esphome::duty_time_sensor::DutyTimeSensor, esphome::ee895::EE895Component, esphome::esp32_dac::ESP32DAC, esphome::honeywellabp::HONEYWELLABPSensor, esphome::htu21d::HTU21DComponent, esphome::mcp3204::MCP3204, esphome::mmc5603::MMC5603Component, esphome::mqtt::MQTTCoverComponent, esphome::mqtt_subscribe::MQTTSubscribeSensor, esphome::mqtt_subscribe::MQTTSubscribeTextSensor, esphome::pid::PIDClimate, esphome::sht3xd::SHT3XDComponent, esphome::shtcx::SHTCXComponent, esphome::tm1621::TM1621Display, esphome::tuya::TuyaCover, esphome::tuya::TuyaLight, esphome::uart::ESP32ArduinoUARTComponent, esphome::fs3000::FS3000Component, esphome::hte501::HTE501Component, esphome::kalman_combinator::KalmanCombinatorComponent, esphome::max44009::MAX44009Sensor, esphome::mcp23s08::MCP23S08, esphome::mcp23s17::MCP23S17, esphome::mhz19::MHZ19Component, esphome::modbus::Modbus, esphome::pcf8574::PCF8574Component, esphome::pzem004t::PZEM004T, esphome::rc522::RC522, esphome::sdp3x::SDP3XComponent, esphome::sntp::SNTPComponent, esphome::ssd1351_base::SSD1351, esphome::touchscreen::TouchscreenBinarySensor, esphome::x9c::X9cOutput, esphome::xgzp68xx::XGZP68XXComponent, esphome::adc128s102::ADC128S102, esphome::feedback::FeedbackCover, esphome::gp8403::GP8403, esphome::gpio::GPIOBinarySensor, esphome::hdc1080::HDC1080Component, esphome::pn532_spi::PN532Spi, esphome::sn74hc165::SN74HC165Component, esphome::spi_led_strip::SpiLedStrip, esphome::ssd1306_spi::SPISSD1306, esphome::ssd1322_base::SSD1322, esphome::ssd1322_spi::SPISSD1322, esphome::ssd1325_spi::SPISSD1325, esphome::ssd1327_base::SSD1327, esphome::ssd1327_spi::SPISSD1327, esphome::ssd1331_spi::SPISSD1331, esphome::ssd1351_spi::SPISSD1351, esphome::tt21100::TT21100Button, esphome::uart::LibreTinyUARTComponent, esphome::a4988::A4988, esphome::ens210::ENS210Component, esphome::i2s_audio::I2SAudioMicrophone, esphome::iaqcore::IAQCore, esphome::max6675::MAX6675Sensor, esphome::max6956::MAX6956LedChannel, esphome::mcp23008::MCP23008, esphome::mcp23017::MCP23017, esphome::mlx90393::MLX90393Cls, esphome::ntc::NTC, esphome::pca6416a::PCA6416AComponent, esphome::pca9554::PCA9554Component, esphome::pm1006::PM1006Component, esphome::pmwcs3::PMWCS3Component, esphome::sfa30::SFA30Component, esphome::sts3x::STS3XComponent, esphome::sx1509::SX1509FloatOutputChannel, esphome::template_::TemplateNumber, esphome::template_::TemplateSelect, esphome::yashima::YashimaClimate, esphome::atm90e26::ATM90E26Component, esphome::atm90e32::ATM90E32Component, esphome::cd74hc4067::CD74HC4067Component, esphome::current_based::CurrentBasedCover, esphome::gpio::GPIOBinaryOutput, esphome::ina219::INA219Component, esphome::mcp4725::MCP4725, esphome::output::OutputSwitch, esphome::sm2235::SM2235, esphome::sm2335::SM2335, esphome::speed::SpeedFan, esphome::template_::TemplateSwitch, esphome::tuya::TuyaSelect, esphome::uart::IDFUARTComponent, esphome::analog_threshold::AnalogThresholdBinarySensor, esphome::endstop::EndstopCover, esphome::homeassistant::HomeassistantBinarySensor, esphome::homeassistant::HomeassistantSensor, esphome::homeassistant::HomeassistantTextSensor, esphome::lcd_pcf8574::PCF8574LCDDisplay, esphome::mmc5983::MMC5983Component, esphome::spi_device::SPIDeviceComponent, esphome::status::StatusBinarySensor, esphome::tee501::TEE501Component, esphome::template_::TemplateBinarySensor, esphome::tmp102::TMP102Component, esphome::tuya::TuyaFan, esphome::aht10::AHT10Component, esphome::am2320::AM2320Component, esphome::binary::BinaryFan, esphome::bmi160::BMI160Component, 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::demo::DemoSwitch, esphome::dht12::DHT12Component, esphome::ds1307::DS1307Component, esphome::gcja5::GCJA5Component, esphome::homeassistant::HomeassistantTime, esphome::ina226::INA226Component, esphome::ina260::INA260Component, esphome::ina3221::INA3221Component, esphome::lcd_gpio::GPIOLCDDisplay, esphome::mcp9808::MCP9808Sensor, esphome::mlx90614::MLX90614Component, esphome::mpu6050::MPU6050Component, esphome::mpu6886::MPU6886Component, esphome::ms5611::MS5611Component, esphome::pcf85063::PCF85063Component, esphome::pcf8563::PCF8563Component, esphome::preferences::IntervalSyncer, esphome::ssd1306_i2c::I2CSSD1306, esphome::ssd1327_i2c::I2CSSD1327, esphome::ssd1331_base::SSD1331, esphome::time_based::TimeBasedCover, esphome::tmp117::TMP117Component, esphome::tof10120::TOF10120Sensor, esphome::tuya::TuyaBinarySensor, esphome::tuya::TuyaClimate, esphome::tuya::TuyaNumber, esphome::tuya::TuyaSensor, esphome::tuya::TuyaSwitch, esphome::tuya::TuyaTextSensor, esphome::version::VersionTextSensor, and esphome::demo::DemoBinarySensor.
Definition at line 47 of file component.cpp.
void esphome::Component::status_clear_error | ( | ) |
Definition at line 154 of file component.cpp.
void esphome::Component::status_clear_warning | ( | ) |
Definition at line 153 of file component.cpp.
bool esphome::Component::status_has_error | ( | ) |
Definition at line 144 of file component.cpp.
bool esphome::Component::status_has_warning | ( | ) |
Definition at line 143 of file component.cpp.
void esphome::Component::status_momentary_error | ( | const std::string & | name, |
uint32_t | length = 5000 |
||
) |
Definition at line 159 of file component.cpp.
void esphome::Component::status_momentary_warning | ( | const std::string & | name, |
uint32_t | length = 5000 |
||
) |
Definition at line 155 of file component.cpp.
void esphome::Component::status_set_error | ( | ) |
Definition at line 149 of file component.cpp.
void esphome::Component::status_set_warning | ( | ) |
Definition at line 145 of file component.cpp.
|
protected |
Definition at line 273 of file component.h.
|
protected |
State of this component.
Definition at line 271 of file component.h.
|
protected |
Definition at line 272 of file component.h.