Skip to content

Commit

Permalink
Rename ValueConsumer::set_input to set
Browse files Browse the repository at this point in the history
  • Loading branch information
mairas committed Feb 8, 2024
1 parent c3cfd29 commit b64f6b9
Show file tree
Hide file tree
Showing 62 changed files with 103 additions and 94 deletions.
8 changes: 4 additions & 4 deletions src/sensesp/controllers/smart_switch_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,12 @@ SmartSwitchController::SmartSwitchController(bool auto_initialize,
}
}

void SmartSwitchController::set_input(bool new_value, uint8_t input_channel) {
void SmartSwitchController::set(bool new_value, uint8_t input_channel) {
is_on = new_value;
this->emit(is_on);
}

void SmartSwitchController::set_input(ClickTypes new_value,
void SmartSwitchController::set(ClickTypes new_value,
uint8_t input_channel) {
if (!ClickType::is_click(new_value)) {
// Ignore button presses (we only want interpreted clicks)
Expand All @@ -52,12 +52,12 @@ void SmartSwitchController::set_input(ClickTypes new_value,
// Sync any specified sync paths...
for (auto& path : sync_paths) {
debugD("Sync status to %s", path.sk_sync_path.c_str());
path.put_request->set_input(is_on);
path.put_request->set(is_on);
}
}
}

void SmartSwitchController::set_input(String new_value, uint8_t input_channel) {
void SmartSwitchController::set(String new_value, uint8_t input_channel) {
if (TextToTruth::is_valid_true(new_value)) {
is_on = true;
} else if (TextToTruth::is_valid_false(new_value)) {
Expand Down
6 changes: 3 additions & 3 deletions src/sensesp/controllers/smart_switch_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +61,9 @@ class SmartSwitchController : public BooleanTransform,
*/
SmartSwitchController(bool auto_initialize = true, String config_path = "",
const char* sk_sync_paths[] = NULL);
void set_input(bool new_value, uint8_t input_channel = 0) override;
void set_input(String new_value, uint8_t input_channel = 0) override;
void set_input(ClickTypes new_value, uint8_t input_channel = 0) override;
void set(bool new_value, uint8_t input_channel = 0) override;
void set(String new_value, uint8_t input_channel = 0) override;
void set(ClickTypes new_value, uint8_t input_channel = 0) override;

// For reading and writing the configuration of this transformation
virtual void get_configuration(JsonObject& doc) override;
Expand Down
4 changes: 2 additions & 2 deletions src/sensesp/controllers/system_status_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

namespace sensesp {

void SystemStatusController::set_input(WiFiState new_value,
void SystemStatusController::set(WiFiState new_value,
uint8_t input_channel) {
// FIXME: If pointers to member functions would be held in an array,
// this would be a simple array dereferencing
Expand All @@ -23,7 +23,7 @@ void SystemStatusController::set_input(WiFiState new_value,
}
}

void SystemStatusController::set_input(WSConnectionState new_value,
void SystemStatusController::set(WSConnectionState new_value,
uint8_t input_channel) {
switch (new_value) {
case WSConnectionState::kWSDisconnected:
Expand Down
4 changes: 2 additions & 2 deletions src/sensesp/controllers/system_status_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,11 @@ class SystemStatusController : public ValueConsumer<WiFiState>,

/// ValueConsumer interface for ValueConsumer<WiFiState> (Networking object
/// state updates)
virtual void set_input(WiFiState new_value,
virtual void set(WiFiState new_value,
uint8_t input_channel = 0) override;
/// ValueConsumer interface for ValueConsumer<WSConnectionState>
/// (WSClient object state updates)
virtual void set_input(WSConnectionState new_value,
virtual void set(WSConnectionState new_value,
uint8_t input_channel = 0) override;

protected:
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/net/ws_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ void WSClient::process_received_updates() {
}
}
release_received_updates_semaphore();
delta_rx_count_producer_.set_input(num_updates);
delta_rx_count_producer_.set(num_updates);

SKListener::release_semaphore();
}
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/sensors/digital_output.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ DigitalOutput::DigitalOutput(int pin) {
pinMode(pin, OUTPUT);
}

void DigitalOutput::set_input(bool new_value, uint8_t inputChannel) {
void DigitalOutput::set(bool new_value, uint8_t inputChannel) {
digitalWrite(pin_number_, new_value);
this->emit(new_value);
}
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/sensors/digital_output.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ namespace sensesp {
class DigitalOutput : public BooleanTransform {
public:
DigitalOutput(int pin);
void set_input(bool new_value, uint8_t input_channel = 0) override;
void set(bool new_value, uint8_t input_channel = 0) override;

private:
int pin_number_;
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/signalk/signalk_output.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class SKOutput : public SKEmitter, public SymmetricTransform<T> {

SKOutput(String sk_path, SKMetadata* meta) : SKOutput(sk_path, "", meta) {}

virtual void set_input(T new_value, uint8_t input_channel = 0) override {
virtual void set(T new_value, uint8_t input_channel = 0) override {
this->ValueProducer<T>::emit(new_value);
}

Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/signalk/signalk_put_request.h
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ class SKPutRequest : public SKPutRequestBase, public ValueConsumer<T> {
: SKPutRequestBase(sk_path, config_path, timeout),
ignore_duplicates{ignore_duplicates} {}

virtual void set_input(T new_value, uint8_t input_channel = 0) override {
virtual void set(T new_value, uint8_t input_channel = 0) override {
if (ignore_duplicates && new_value == value) {
return;
}
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/system/lambda_consumer.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class LambdaConsumer : public ValueConsumer<IN> {
LambdaConsumer(std::function<void(IN)> function)
: ValueConsumer<IN>(), function{function} {}

void set_input(IN input, uint8_t input_channel = 0) override {
void set(IN input, uint8_t input_channel = 0) override {
function(input);
}

Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/system/pwm_output.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ PWMOutput::PWMOutput(int pin, int pwm_channel) {
}
}

void PWMOutput::set_input(float new_value, uint8_t pwm_channel) {
void PWMOutput::set(float new_value, uint8_t pwm_channel) {
if (pwm_channel == 0) {
// Use the default channel, as zero is the SensESP default
// input_channel for ValueConsumers
Expand Down
4 changes: 2 additions & 2 deletions src/sensesp/system/pwm_output.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ namespace sensesp {
* <p>Channels can be auto-assigned to a pin or they can be declared
* explicitly in your code. The PWM value is set either by
* calling `set_pwm()`, or by using an instance of `PWMOutput`
* and calling the `set_input()` method as defined in `ValueConsumer<>`.
* and calling the `set()` method as defined in `ValueConsumer<>`.
* <p>On an esp32, the "channel" corresponds to one of the timer
* channels available on the onboard chip. Explicit declaration
* of a channel may or may not be necessary depending on other
Expand Down Expand Up @@ -48,7 +48,7 @@ class PWMOutput : public ValueConsumer<float> {
* pwm_channel is zero, the channel assigned when the PWMOutput instance
* was instantiated will be used.
*/
virtual void set_input(float new_value, uint8_t pwm_channel = 0) override;
virtual void set(float new_value, uint8_t pwm_channel = 0) override;

/**
* Assigns the specified GPIO pin to the specified pwm channel.
Expand Down
8 changes: 4 additions & 4 deletions src/sensesp/system/rgb_led.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ static float get_pwm(long rgb, int shift_right, bool common_anode) {
}
}

void RgbLed::set_input(long new_value, uint8_t input_channel) {
void RgbLed::set(long new_value, uint8_t input_channel) {
if (led_r_channel_ >= 0) {
float r = get_pwm(new_value, 16, common_anode_);
PWMOutput::set_pwm(led_r_channel_, r);
Expand All @@ -49,11 +49,11 @@ void RgbLed::set_input(long new_value, uint8_t input_channel) {
}
}

void RgbLed::set_input(bool new_value, uint8_t input_channel) {
void RgbLed::set(bool new_value, uint8_t input_channel) {
if (new_value) {
set_input(led_on_rgb_, input_channel);
set(led_on_rgb_, input_channel);
} else {
set_input(led_off_rgb_, input_channel);
set(led_off_rgb_, input_channel);
}
}

Expand Down
8 changes: 4 additions & 4 deletions src/sensesp/system/rgb_led.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@ namespace sensesp {
* depth numbers composed of three 8 bit channels for Red, Green,
* and Blue (see https://techterms.com/definition/rgb)
* <p>Color LEDs can be controlled by either setting the specific
* color to be displayed via the set_input(long), or by setting the
* on/off state via set_input(bool). When specifying a simple on/off
* color to be displayed via the set(long), or by setting the
* on/off state via set(bool). When specifying a simple on/off
* via the the bool input, the default ON or OFF colors specified in the
* constructor are used.
* <p>You do not have to define all three channels (for example, if
Expand Down Expand Up @@ -55,14 +55,14 @@ class RgbLed : public Configurable,
* Used to set the current display state of the LED.
* @param new_value The RGB color to display.
*/
virtual void set_input(long new_value, uint8_t input_channel = 0) override;
virtual void set(long new_value, uint8_t input_channel = 0) override;

/**
* Used to set the current display state of the LED with a simple on/off
* boolean value. Using TRUE for new_value sets the color to the ON color.
* Using FALSE uses the OFF color.
*/
virtual void set_input(bool new_value, uint8_t input_channel = 0) override;
virtual void set(bool new_value, uint8_t input_channel = 0) override;

virtual void get_configuration(JsonObject& doc) override;
virtual bool set_configuration(const JsonObject& config) override;
Expand Down
4 changes: 2 additions & 2 deletions src/sensesp/system/system_status_led.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ void SystemStatusLed::set_ws_connected() {
blinker_->set_pattern(ws_connected_pattern);
}

void SystemStatusLed::set_input(SystemStatus new_value, uint8_t input_channel) {
void SystemStatusLed::set(SystemStatus new_value, uint8_t input_channel) {
switch (new_value) {
case SystemStatus::kWifiNoAP:
this->set_wifi_no_ap();
Expand All @@ -82,7 +82,7 @@ void SystemStatusLed::set_input(SystemStatus new_value, uint8_t input_channel) {
}
}

void SystemStatusLed::set_input(int new_value, uint8_t input_channel) {
void SystemStatusLed::set(int new_value, uint8_t input_channel) {
blinker_->blip();
}

Expand Down
4 changes: 2 additions & 2 deletions src/sensesp/system/system_status_led.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@ class SystemStatusLed : public ValueConsumer<SystemStatus>,
public:
SystemStatusLed(int pin);

virtual void set_input(SystemStatus new_value,
virtual void set(SystemStatus new_value,
uint8_t input_channel = 0) override;
virtual void set_input(int new_value, uint8_t input_channel = 0) override;
virtual void set(int new_value, uint8_t input_channel = 0) override;
};

} // namespace sensesp
Expand Down
15 changes: 12 additions & 3 deletions src/sensesp/system/valueconsumer.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class ValueProducer;
/**
* @brief A base class for piece of code (like a transform) that
* accepts data for input. ValueConsumers can accept one or more input values
* via the set_input() method. They are connected to `ValueProducers`
* via the set() method. They are connected to `ValueProducers`
* via the `connect_to()` method.
* @see ValueProducer::connect_to()
*/
Expand All @@ -29,7 +29,16 @@ class ValueConsumer {
* This parameter allows you to specify which input number the producer
* is connecting to. For single input consumers, leave the index at zero.
*/
virtual void set_input(T new_value, uint8_t input_channel = 0) {}
virtual void set(T new_value, uint8_t input_channel = 0) {}

virtual void set_input(T new_value, uint8_t input_channel = 0) {
static bool warned = false;
if (!warned) {
warned = true;
debugW("set_input() is deprecated. Use set() instead.");
}
set(new_value, input_channel);
}

/**
* Registers this consumer with the specified producer, letting it
Expand All @@ -41,7 +50,7 @@ class ValueConsumer {
*/
void connect_from(ValueProducer<T>* producer, uint8_t input_channel = 0) {
producer->attach([producer, this, input_channel]() {
this->set_input(producer->get(), input_channel);
this->set(producer->get(), input_channel);
});
}
};
Expand Down
12 changes: 6 additions & 6 deletions src/sensesp/system/valueproducer.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@ class ValueProducer : virtual public Observable {
* This parameter allows you to specify which input number this producer
* is connecting to. For single input consumers, leave the index at
* zero.
* @see ValueConsumer::set_input()
* @see ValueConsumer::set()
*/
void connect_to(ValueConsumer<T>* consumer, uint8_t input_channel = 0) {
this->attach([this, consumer, input_channel]() {
consumer->set_input(this->get(), input_channel);
consumer->set(this->get(), input_channel);
});
}

Expand All @@ -59,7 +59,7 @@ class ValueProducer : virtual public Observable {
template <typename CT>
void connect_to(ValueConsumer<CT>* consumer, uint8_t input_channel = 0) {
this->attach([this, consumer, input_channel]() {
consumer->set_input(CT(this->get()), input_channel);
consumer->set(CT(this->get()), input_channel);
});
}

Expand All @@ -72,13 +72,13 @@ class ValueProducer : virtual public Observable {
* This parameter allows you to specify which input number this producer
* is connecting to. For single input consumers, leave the index at
* zero.
* @see ValueConsumer::set_input()
* @see ValueConsumer::set()
*/
template <typename T2>
Transform<T, T2>* connect_to(Transform<T, T2>* consumer_producer,
uint8_t input_channel = 0) {
this->attach([this, consumer_producer, input_channel]() {
consumer_producer->set_input(T(this->get()), input_channel);
consumer_producer->set(T(this->get()), input_channel);
});
return consumer_producer;
}
Expand All @@ -99,7 +99,7 @@ class ValueProducer : virtual public Observable {
Transform<TT, T2>* connect_to(Transform<TT, T2>* consumer_producer,
uint8_t input_channel = 0) {
this->attach([this, consumer_producer, input_channel]() {
consumer_producer->set_input(TT(this->get()), input_channel);
consumer_producer->set(TT(this->get()), input_channel);
});
return consumer_producer;
}
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/air_density.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ namespace sensesp {

AirDensity::AirDensity() : FloatTransform() {}

void AirDensity::set_input(float input, uint8_t inputChannel) {
void AirDensity::set(float input, uint8_t inputChannel) {
inputs[inputChannel] = input;
received |= 1 << inputChannel;
if (received ==
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/air_density.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ namespace sensesp {
class AirDensity : public FloatTransform {
public:
AirDensity();
virtual void set_input(float input, uint8_t inputChannel) override;
virtual void set(float input, uint8_t inputChannel) override;

private:
uint8_t received = 0;
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/analogvoltage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ AnalogVoltage::AnalogVoltage(float max_voltage, float multiplier, float offset,
load_configuration();
}

void AnalogVoltage::set_input(float input, uint8_t inputChannel) {
void AnalogVoltage::set(float input, uint8_t inputChannel) {
this->emit(((input * (max_voltage_ / MAX_ANALOG_OUTPUT)) * multiplier_) +
offset_);
}
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/analogvoltage.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class AnalogVoltage : public FloatTransform {
public:
AnalogVoltage(float max_voltage = 3.3, float multiplier = 1.0,
float offset = 0.0, String config_path = "");
virtual void set_input(float input, uint8_t inputChannel = 0) override;
virtual void set(float input, uint8_t inputChannel = 0) override;
virtual void get_configuration(JsonObject& doc) override;
virtual bool set_configuration(const JsonObject& config) override;
virtual String get_config_schema() override;
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/angle_correction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ AngleCorrection::AngleCorrection(float offset, float min_angle,
load_configuration();
}

void AngleCorrection::set_input(float input, uint8_t inputChannel) {
void AngleCorrection::set(float input, uint8_t inputChannel) {
// first the correction
float x = input + offset_;

Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/angle_correction.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ namespace sensesp {
class AngleCorrection : public FloatTransform {
public:
AngleCorrection(float offset, float min_angle = 0, String config_path = "");
virtual void set_input(float input, uint8_t inputChannel = 0) override;
virtual void set(float input, uint8_t inputChannel = 0) override;
virtual void get_configuration(JsonObject& doc) override;
virtual bool set_configuration(const JsonObject& config) override;
virtual String get_config_schema() override;
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/change_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ ChangeFilter::ChangeFilter(float min_delta, float max_delta, int max_skips,
skips_ = max_skips_ + 1;
}

void ChangeFilter::set_input(float new_value, uint8_t input_channel) {
void ChangeFilter::set(float new_value, uint8_t input_channel) {
float delta = absf(new_value - output);
if ((delta >= min_delta_ && delta <= max_delta_) || skips_ > max_skips_) {
skips_ = 0;
Expand Down
2 changes: 1 addition & 1 deletion src/sensesp/transforms/change_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class ChangeFilter : public FloatTransform {
ChangeFilter(float min_delta = 0.0, float max_delta = 9999.0,
int max_skips = 99, String config_path = "");

virtual void set_input(float new_value, uint8_t input_channel = 0) override;
virtual void set(float new_value, uint8_t input_channel = 0) override;
virtual void get_configuration(JsonObject& doc) override;
virtual bool set_configuration(const JsonObject& config) override;
virtual String get_config_schema() override;
Expand Down
Loading

0 comments on commit b64f6b9

Please sign in to comment.