ESPHome
2024.10.3
|
This class simplifies creating components that periodically check a state. More...
#include <component.h>
Public Member Functions | |
PollingComponent () | |
PollingComponent (uint32_t update_interval) | |
Initialize this polling component with the given update interval in ms. More... | |
virtual void | set_update_interval (uint32_t update_interval) |
Manually set the update interval in ms for this polling object. More... | |
virtual void | update ()=0 |
void | call_setup () override |
virtual uint32_t | get_update_interval () const |
Get the update interval in ms of this sensor. More... | |
void | start_poller () |
void | stop_poller () |
Public Member Functions inherited from esphome::Component | |
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 () 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. More... | |
const char * | get_component_source () const |
Get the integration where this component was declared as a string. More... | |
Protected Attributes | |
uint32_t | update_interval_ |
Protected Attributes inherited from esphome::Component | |
uint32_t | component_state_ {0x0000} |
State of this component. More... | |
float | setup_priority_override_ {NAN} |
const char * | component_source_ {nullptr} |
Additional Inherited Members | |
Protected Member Functions inherited from esphome::Component | |
virtual void | call_loop () |
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... | |
This class simplifies creating components that periodically check a state.
You basically just need to implement the update() function, it will be called every update_interval ms after startup. Note that this class cannot guarantee a correct timing, as it's not using timers, just a software polling feature with set_interval() from Component.
Definition at line 283 of file component.h.
|
inline |
Definition at line 285 of file component.h.
|
explicit |
Initialize this polling component with the given update interval in ms.
update_interval | The update interval in ms. |
Definition at line 208 of file component.cpp.
|
overridevirtual |
Reimplemented from esphome::Component.
Definition at line 210 of file component.cpp.
|
virtual |
Get the update interval in ms of this sensor.
Definition at line 228 of file component.cpp.
|
virtual |
Manually set the update interval in ms for this polling object.
Override this if you want to do some validation for the update interval.
update_interval | The update interval in ms. |
Definition at line 229 of file component.cpp.
void esphome::PollingComponent::start_poller | ( | ) |
Definition at line 218 of file component.cpp.
void esphome::PollingComponent::stop_poller | ( | ) |
Definition at line 223 of file component.cpp.
|
pure virtual |
Implemented in esphome::nextion::Nextion, esphome::modbus_controller::ModbusController, esphome::tsl2591::TSL2591Component, esphome::st7789v::ST7789V, esphome::inkplate6::Inkplate6, esphome::micronova::MicroNova, esphome::ina2xx_base::INA2XX, esphome::bedjet::BedJetHub, esphome::lvgl::LvglComponent, esphome::bl0942::BL0942, esphome::wifi_info::BSSIDWiFiInfo, esphome::veml7700::VEML7700Component, esphome::bme680::BME680Component, esphome::fingerprint_grow::FingerprintGrowComponent, esphome::mpl3115a2::MPL3115A2Component, esphome::wifi_info::SSIDWiFiInfo, esphome::kamstrup_kmp::KamstrupKMPComponent, esphome::ili9xxx::ILI9XXXDisplay, esphome::qmp6988::QMP6988Component, esphome::sun::SunTrigger, esphome::ade7880::ADE7880, esphome::max31856::MAX31856Sensor, esphome::ade7953_base::ADE7953, esphome::as7341::AS7341Component, esphome::touchscreen::Touchscreen, esphome::bme280_base::BME280Component, esphome::havells_solar::HavellsSolar, esphome::pulse_counter::PulseCounterSensor, esphome::bmp3xx_base::BMP3XXComponent, esphome::sgp4x::SGP4xComponent, esphome::bl0939::BL0939, esphome::bl0940::BL0940, esphome::zyaura::ZyAuraSensor, esphome::daly_bms::DalyBmsComponent, esphome::bmp581::BMP581Component, esphome::sen21231_sensor::Sen21231Sensor, esphome::tsl2561::TSL2561Sensor, esphome::bmp280_base::BMP280Component, esphome::nau7802::NAU7802Sensor, esphome::pid::PIDSimulator, esphome::template_::TemplateText, esphome::veml3235::VEML3235Sensor, esphome::wifi_info::ScanResultsWiFiInfo, esphome::qspi_amoled::QspiAmoLed, esphome::tmp1075::TMP1075Sensor, esphome::sdm_meter::SDMMeter, esphome::tcs34725::TCS34725Component, esphome::online_image::OnlineImage, esphome::sen5x::SEN5XComponent, esphome::sim800l::Sim800LComponent, esphome::addressable_light::AddressableLightDisplay, esphome::statsd::StatsdComponent, esphome::dht::DHT, esphome::ltr390::LTR390Component, esphome::adc::ADCSensor, esphome::hydreon_rgxx::HydreonRGxxComponent, esphome::ina226::INA226Component, esphome::apds9306::APDS9306, esphome::cd74hc4067::CD74HC4067Sensor, esphome::st7735::ST7735, esphome::udp::UDPComponent, esphome::pcd8544::PCD8544, esphome::dps310::DPS310Component, esphome::gps::GPS, esphome::pvvx_mithermometer::PVVXDisplay, esphome::ethernet_info::DNSAddressEthernetInfo, esphome::hmc5883l::HMC5883LComponent, esphome::max9611::MAX9611Component, esphome::wifi_info::DNSAddressWifiInfo, esphome::st7567_base::ST7567, esphome::alpha3::Alpha3, esphome::ezo::EZOSensor, esphome::max7219digit::MAX7219Component, esphome::max31865::MAX31865Sensor, esphome::ms8607::MS8607Component, esphome::pn532::PN532, esphome::tm1637::TM1637Display, esphome::pulse_width::PulseWidthSensor, esphome::ufire_ise::UFireISEComponent, esphome::hlw8012::HLW8012Component, esphome::tm1621::TM1621Display, esphome::am2315c::AM2315C, esphome::pmsa003i::PMSA003IComponent, esphome::qmc5883l::QMC5883LComponent, esphome::st7701s::ST7701S, esphome::vl53l0x::VL53L0XSensor, esphome::sgp30::SGP30Component, esphome::sigma_delta_output::SigmaDeltaOutput, esphome::ssd1306_base::SSD1306, esphome::wireguard::Wireguard, esphome::cse7761::CSE7761Component, esphome::ltr501::LTRAlsPs501Component, esphome::ltr_als_ps::LTRAlsPsComponent, esphome::ufire_ec::UFireECComponent, esphome::ags10::AGS10Component, esphome::pylontech::PylontechComponent, esphome::teleinfo::TeleInfo, esphome::airthings_wave_base::AirthingsWaveBase, esphome::ezo_pmp::EzoPMP, esphome::hbridge::HBridgeLightOutput, esphome::t6615::T6615Component, esphome::tm1638::TM1638Component, esphome::waveshare_epaper::WaveshareEPaperBase, esphome::duty_cycle::DutyCycleSensor, esphome::hm3301::HM3301Component, esphome::hx711::HX711Sensor, esphome::sntp::SNTPComponent, esphome::sps30::SPS30Component, esphome::st7920::ST7920, esphome::radon_eye_rd200::RadonEyeRD200, esphome::sen0321_sensor::Sen0321Sensor, esphome::shelly_dimmer::ShellyDimmer, esphome::ultrasonic::UltrasonicSensorComponent, esphome::anova::Anova, esphome::atm90e32::ATM90E32Component, esphome::lcd_base::LCDDisplay, esphome::lightwaverf::LightWaveRF, esphome::max7219::MAX7219Component, esphome::mcp9600::MCP9600Component, esphome::scd4x::SCD4XComponent, esphome::ccs811::CCS811Component, esphome::htu21d::HTU21DComponent, esphome::pzemac::PZEMAC, esphome::rpi_dpi_rgb::RpiDpiRgb, esphome::ssd1325_base::SSD1325, esphome::bh1750::BH1750Sensor, esphome::ble_client::BLESensor, esphome::growatt_solar::GrowattSolar, esphome::max31855::MAX31855Sensor, esphome::sht4x::SHT4XComponent, esphome::jsn_sr04t::Jsnsr04tComponent, esphome::sm300d2::SM300D2Sensor, esphome::am43::Am43, esphome::debug::DebugComponent, esphome::kmeteriso::KMeterISOComponent, esphome::kuntze::Kuntze, esphome::mmc5603::MMC5603Component, esphome::npi19::NPI19Component, esphome::pzem004t::PZEM004T, esphome::rc522::RC522, esphome::sht3xd::SHT3XDComponent, esphome::shtcx::SHTCXComponent, esphome::ssd1351_base::SSD1351, esphome::tem3200::TEM3200Component, esphome::template_::TemplateDate, esphome::template_::TemplateDateTime, esphome::template_::TemplateTime, esphome::adc128s102::ADC128S102Sensor, esphome::ads1115::ADS1115Sensor, esphome::bedjet::BedJetClimate, esphome::ee895::EE895Component, esphome::honeywellabp2_i2c::HONEYWELLABP2Sensor, esphome::max44009::MAX44009Sensor, esphome::mcp3008::MCP3008Sensor, esphome::mcp3204::MCP3204Sensor, esphome::pzemdc::PZEMDC, esphome::ssd1322_base::SSD1322, esphome::ssd1327_base::SSD1327, esphome::sun::SunSensor, esphome::ads1118::ADS1118Sensor, esphome::ble_client::BLEClientRSSISensor, esphome::ble_client::BLETextSensor, esphome::duty_time_sensor::DutyTimeSensor, esphome::ens160_base::ENS160Component, esphome::hdc1080::HDC1080Component, esphome::honeywellabp::HONEYWELLABPSensor, esphome::hte501::HTE501Component, esphome::max6675::MAX6675Sensor, esphome::sdl::Sdl, esphome::sun::SunTextSensor, esphome::bedjet::BedJetFan, esphome::fs3000::FS3000Component, esphome::mhz19::MHZ19Component, esphome::mlx90393::MLX90393Cls, esphome::nextion::NextionBinarySensor, esphome::pm1006::PM1006Component, esphome::smt100::SMT100Component, esphome::sts3x::STS3XComponent, esphome::zio_ultrasonic::ZioUltrasonicComponent, esphome::aht10::AHT10Component, esphome::atm90e26::ATM90E26Component, esphome::emc2101::EMC2101Sensor, esphome::hyt271::HYT271Component, esphome::ina219::INA219Component, esphome::nextion::NextionSensor, esphome::sfa30::SFA30Component, esphome::bmp085::BMP085Component, esphome::ens210::ENS210Component, esphome::honeywell_hih_i2c::HoneywellHIComponent, esphome::http_request::HttpRequestUpdate, esphome::iaqcore::IAQCore, esphome::mcp9808::MCP9808Sensor, esphome::pmwcs3::PMWCS3Component, esphome::senseair::SenseAirComponent, esphome::ssd1331_base::SSD1331, esphome::tee501::TEE501Component, esphome::template_::TemplateNumber, esphome::template_::TemplateSelect, esphome::tmp102::TMP102Component, esphome::tof10120::TOF10120Sensor, esphome::xgzp68xx::XGZP68XXComponent, esphome::am2320::AM2320Component, esphome::as5600::AS5600Sensor, esphome::bmi160::BMI160Component, esphome::dht12::DHT12Component, esphome::esp32_hall::ESP32HallSensor, esphome::m5stack_8angle::M5Stack8AngleSwitchBinarySensor, esphome::m5stack_8angle::M5Stack8AngleKnobSensor, esphome::mpu6050::MPU6050Component, esphome::mpu6886::MPU6886Component, esphome::ms5611::MS5611Component, esphome::nextion::NextionSwitch, esphome::sdp3x::SDP3XComponent, esphome::tmp117::TMP117Component, esphome::ethernet_info::IPAddressEthernetInfo, esphome::gps::GPSTime, esphome::htu31d::HTU31DComponent, esphome::ina260::INA260Component, esphome::ina3221::INA3221Component, esphome::mlx90614::MLX90614Component, esphome::nextion::NextionTextSensor, esphome::template_::TemplateTextSensor, esphome::wifi_info::IPAddressWiFiInfo, esphome::ct_clamp::CTClampSensor, esphome::dallas_temp::DallasTemperatureSensor, esphome::ds1307::DS1307Component, esphome::gp2y1010au0f::GP2Y1010AU0FSensor, esphome::homeassistant::HomeassistantTime, esphome::internal_temperature::InternalTemperatureSensor, esphome::pcf85063::PCF85063Component, esphome::pcf8563::PCF8563Component, esphome::template_::TemplateSensor, esphome::wifi_signal::WiFiSignalSensor, esphome::demo::DemoBinarySensor, esphome::demo::DemoSensor, esphome::demo::DemoTextSensor, esphome::mmc5983::MMC5983Component, esphome::host::HostTime, esphome::interval::IntervalTrigger, and esphome::uptime::UptimeSecondsSensor.
|
protected |
Definition at line 319 of file component.h.