migrate callbacks from std::vector to std::map

This commit is contained in:
Siwat Sirichai 2023-12-31 13:29:11 +07:00
parent c635427d64
commit 5f6e586945
11 changed files with 143 additions and 178 deletions

View File

@ -5,10 +5,11 @@ AnalogCard::AnalogCard() : dac0(DAC0_ADDRESS),
dac1(DAC1_ADDRESS), dac1(DAC1_ADDRESS),
dac2(DAC2_ADDRESS), dac2(DAC2_ADDRESS),
dac3(DAC3_ADDRESS), dac3(DAC3_ADDRESS),
analogInputBankA(), analogInputBankA(),
analogInputBankB(), analogInputBankB(),
dac_change_callbacks() dac_change_callbacks()
{ {
this->handler_count = 0;
} }
void AnalogCard::dacWrite(uint8_t pin, uint16_t value) void AnalogCard::dacWrite(uint8_t pin, uint16_t value)
@ -22,10 +23,10 @@ void AnalogCard::setDACState(uint8_t pin, bool state)
{ {
ESP_LOGD("AnalogCard", "Setting DAC state: %d, %d", pin, state); ESP_LOGD("AnalogCard", "Setting DAC state: %d, %d", pin, state);
this->dac_state[pin] = state; this->dac_state[pin] = state;
this->sendDataToDAC(pin, this->dac_value[pin]*state); this->sendDataToDAC(pin, this->dac_value[pin] * state);
for (int i = 0; i < this->dac_change_callbacks.size(); i++) for (const auto& callback : this->dac_change_callbacks)
{ {
this->dac_change_callbacks[i](pin, state, this->dac_value[pin]); callback.second(pin, state, this->dac_value[pin]);
} }
} }
@ -33,12 +34,13 @@ void AnalogCard::setDACValue(uint8_t pin, uint16_t value)
{ {
ESP_LOGD("AnalogCard", "Setting DAC value: %d, %d", pin, value); ESP_LOGD("AnalogCard", "Setting DAC value: %d, %d", pin, value);
this->dac_value[pin] = value; this->dac_value[pin] = value;
this->sendDataToDAC(pin, value*this->dac_state[pin]); this->sendDataToDAC(pin, value * this->dac_state[pin]);
for (int i = 0; i < this->dac_change_callbacks.size(); i++) for (const auto& callback : this->dac_change_callbacks)
{ {
this->dac_change_callbacks[i](pin, this->dac_state[pin], value); callback.second(pin, this->dac_state[pin], value);
} }
} }
uint16_t AnalogCard::getDACValue(uint8_t pin) uint16_t AnalogCard::getDACValue(uint8_t pin)
{ {
@ -124,20 +126,13 @@ uint8_t AnalogCard::getType()
return CARD_TYPE_ANALOG; return CARD_TYPE_ANALOG;
} }
void AnalogCard::registerDACChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback) uint8_t AnalogCard::registerDACChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback)
{ {
this->dac_change_callbacks.push_back(callback); this->dac_change_callbacks[this->handler_count] = callback;
return this->handler_count++;
} }
// void AnalogCard::deregisterDACChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback) void AnalogCard::deregisterDACChangeCallback(uint8_t handler)
// { {
// for (int i = 0; i < this->dac_change_callbacks.size(); i++) this->dac_change_callbacks.erase(handler);
// { }
// if (this->dac_change_callbacks[i].target<void(uint8_t, bool, uint16_t)>() == callback.target<void(uint8_t, bool, uint16_t)>())
// {
// this->dac_change_callbacks.erase(this->dac_change_callbacks.begin() + i);
// break;
// }
// }
// }

View File

@ -3,6 +3,7 @@
#include <Adafruit_ADS1X15.h> #include <Adafruit_ADS1X15.h>
#include <MCP4725.h> #include <MCP4725.h>
#include <vector> #include <vector>
#include <map>
#define CARD_TYPE_ANALOG 0x02 #define CARD_TYPE_ANALOG 0x02
@ -25,11 +26,12 @@ class AnalogCard : public ExpansionCard {
uint16_t getDACValue(uint8_t pin); uint16_t getDACValue(uint8_t pin);
void setDACState(uint8_t pin, bool state); void setDACState(uint8_t pin, bool state);
void setDACValue(uint8_t pin, uint16_t value); void setDACValue(uint8_t pin, uint16_t value);
void registerDACChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback); uint8_t registerDACChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback);
//void deregisterDACChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback); void deregisterDACChangeCallback(uint8_t handler);
uint8_t getType(); uint8_t getType();
private: private:
std::vector<std::function<void(uint8_t, bool, uint16_t)>> dac_change_callbacks; uint8_t handler_count;
std::map<uint8_t, std::function<void(uint8_t, bool, uint16_t)>> dac_change_callbacks;
bool dac_state[4]; bool dac_state[4];
uint16_t dac_value[4]; uint16_t dac_value[4];
MCP4725 dac0; MCP4725 dac0;

View File

@ -5,6 +5,7 @@ AnalogIoT::AnalogIoT() : adc_conversion_callbacks() {
adc_publish_enabled[i] = false; adc_publish_enabled[i] = false;
adc_conversion_interval[i] = 1000; adc_conversion_interval[i] = 1000;
} }
this->adc_conversion_callback_index = 0;
} }
AnalogIoT::~AnalogIoT() { AnalogIoT::~AnalogIoT() {
@ -49,8 +50,8 @@ void AnalogIoT::publishADC(uint8_t pin) {
delete[] topic; delete[] topic;
delete[] payload; delete[] payload;
// Call all callbacks // Call all callbacks
for (int i = 0; i < this->adc_conversion_callbacks.size(); i++) { for (auto& callback : this->adc_conversion_callbacks) {
this->adc_conversion_callbacks[i](pin, value); callback.second(pin, value);
} }
} }
} }
@ -65,16 +66,11 @@ void AnalogIoT::setADCsPublishEnabled(bool enabled) {
} }
} }
void AnalogIoT::registerADCConversionCallback(std::function<void(uint8_t, uint16_t)> callback) { void AnalogIoT::registerADCConversionCallback(std::function<void(uint8_t, uint16_t)> callback) {
this->adc_conversion_callbacks.push_back(callback); this->adc_conversion_callbacks[this->adc_conversion_callback_index++] = callback;
}
void AnalogIoT::deregisterADCConversionCallback(uint8_t handler) {
this->adc_conversion_callbacks.erase(handler);
} }
// void AnalogIoT::deregisterADCConversionCallback(std::function<void(uint8_t, uint16_t)> callback) {
// for (int i = 0; i < this->adc_conversion_callbacks.size(); i++) {
// if (this->adc_conversion_callbacks[i].target<void(uint8_t, uint16_t)>() == callback.target<void(uint8_t, uint16_t)>()) {
// this->adc_conversion_callbacks.erase(this->adc_conversion_callbacks.begin() + i);
// break;
// }
// }
// }
void AnalogIoT::setADCConversionInterval(uint8_t pin, uint16_t interval) { void AnalogIoT::setADCConversionInterval(uint8_t pin, uint16_t interval) {
adc_conversion_interval[pin] = interval; adc_conversion_interval[pin] = interval;
} }

View File

@ -1,7 +1,7 @@
#pragma once #pragma once
#include <IoTComponent.hpp> #include <IoTComponent.hpp>
#include <AnalogCard.hpp> #include <AnalogCard.hpp>
#include <vector> #include <map>
#define DAC_SET_STATE_TOPIC "/set/state" #define DAC_SET_STATE_TOPIC "/set/state"
#define DAC_SET_VALUE_TOPIC "/set/value" #define DAC_SET_VALUE_TOPIC "/set/value"
@ -26,7 +26,7 @@ class AnalogIoT : public IoTComponent {
void setADCsPublishInterval(uint32_t interval); void setADCsPublishInterval(uint32_t interval);
void setADCsPublishEnabled(bool enabled); void setADCsPublishEnabled(bool enabled);
void registerADCConversionCallback(std::function<void(uint8_t, uint16_t)> callback); void registerADCConversionCallback(std::function<void(uint8_t, uint16_t)> callback);
// void deregisterADCConversionCallback(std::function<void(uint8_t, uint16_t)> callback); void deregisterADCConversionCallback(uint8_t handler);
void setADCConversionInterval(uint8_t pin, uint16_t interval); void setADCConversionInterval(uint8_t pin, uint16_t interval);
void setADCConversionEnabled(uint8_t pin, bool enabled); void setADCConversionEnabled(uint8_t pin, bool enabled);
bool processADCSetConversionIntervalMessage(char *topic, char *payload, uint8_t topic_length); bool processADCSetConversionIntervalMessage(char *topic, char *payload, uint8_t topic_length);
@ -39,6 +39,7 @@ class AnalogIoT : public IoTComponent {
void loop(); void loop();
uint8_t getType(); uint8_t getType();
private: private:
uint8_t adc_conversion_callback_index = 0;
uint8_t dac_set_state_length; uint8_t dac_set_state_length;
uint8_t dac_set_value_length; uint8_t dac_set_value_length;
uint8_t dac_state_length; uint8_t dac_state_length;
@ -50,5 +51,5 @@ class AnalogIoT : public IoTComponent {
bool adc_publish_enabled[8]; bool adc_publish_enabled[8];
uint16_t adc_conversion_interval[8]; uint16_t adc_conversion_interval[8];
uint32_t last_adc_conversion[8]; uint32_t last_adc_conversion[8];
std::vector<std::function<void(uint8_t, uint16_t)>> adc_conversion_callbacks; std::map<uint8_t, std::function<void(uint8_t, uint16_t)>> adc_conversion_callbacks;
}; };

View File

@ -22,8 +22,6 @@ ClimateCard::ClimateCard(uint8_t ir_pin, AirConditioner ac, uint8_t sensor_type,
this->state.ac_temperature = 25; this->state.ac_temperature = 25;
this->state.ac_mode = 0; this->state.ac_mode = 0;
this->state.ac_fan_speed = 0; this->state.ac_fan_speed = 0;
// Initialize callbacks
this->callbacks = std::vector<std::function<void(uint8_t, uint8_t, uint8_t)>>();
} }
ClimateCard::ClimateCard(uint8_t ir_pin, AirConditioner ac) : ClimateCard(ir_pin, ac, AC_SENSOR_TYPE_NONE, 0) ClimateCard::ClimateCard(uint8_t ir_pin, AirConditioner ac) : ClimateCard(ir_pin, ac, AC_SENSOR_TYPE_NONE, 0)
@ -89,46 +87,24 @@ void ClimateCard::saveStateToFRAM()
fram->write8(fram_address, state.ac_temperature); fram->write8(fram_address, state.ac_temperature);
fram->write8(fram_address + 1, state.ac_mode); fram->write8(fram_address + 1, state.ac_mode);
fram->write8(fram_address + 2, state.ac_fan_speed); fram->write8(fram_address + 2, state.ac_fan_speed);
Serial.println("Saved state to FRAM");
Serial.write(0xFF);
Serial.write(0xFF);
Serial.write(0xFF);
} }
void ClimateCard::loadStateFromFRAM() void ClimateCard::loadStateFromFRAM()
{ {
Serial.print("Loading temperature from FRAM at address "); if (state.ac_temperature > ac.max_temperature)
Serial.print(fram_address); state.ac_temperature = ac.max_temperature;
Serial.print(": "); else if (state.ac_temperature < ac.min_temperature)
Serial.println(fram->read8(fram_address)); state.ac_temperature = ac.min_temperature;
state.ac_temperature = fram->read8(fram_address); // If mode is out of range, set to 0
Serial.print("Loading mode from FRAM at address "); if (state.ac_mode > ac.modes)
Serial.print(fram_address + 1); state.ac_mode = 0;
Serial.print(": "); // If fan speed is out of range, set to 0
Serial.println(fram->read8(fram_address + 1)); if (state.ac_fan_speed > ac.fan_speeds)
state.ac_mode = fram->read8(fram_address + 1); state.ac_fan_speed = 0;
Serial.print("Loading fan speed from FRAM at address ");
Serial.print(fram_address + 2);
Serial.print(": ");
Serial.println(fram->read8(fram_address + 2));
state.ac_fan_speed = fram->read8(fram_address + 2);
Serial.write(0xFF);
Serial.write(0xFF);
Serial.write(0xFF);
// if (state.ac_temperature > ac.max_temperature)
// state.ac_temperature = ac.max_temperature;
// else if (state.ac_temperature < ac.min_temperature)
// state.ac_temperature = ac.min_temperature;
// // If mode is out of range, set to 0
// if (state.ac_mode > ac.modes)
// state.ac_mode = 0;
// // If fan speed is out of range, set to 0
// if (state.ac_fan_speed > ac.fan_speeds)
// state.ac_fan_speed = 0;
updateAirConditioner(); updateAirConditioner();
for (uint8_t i = 0; i < callbacks.size(); i++) for (const auto& callback : callbacks)
{ {
callbacks[i](this->state.ac_mode, this->state.ac_fan_speed, this->state.ac_temperature); callback.second(this->state.ac_mode, this->state.ac_fan_speed, this->state.ac_temperature);
} }
} }
@ -163,11 +139,7 @@ void ClimateCard::setFanSpeed(uint8_t fan_speed)
void ClimateCard::registerChangeCallback(std::function<void(uint8_t, uint8_t, uint8_t)> callback) void ClimateCard::registerChangeCallback(std::function<void(uint8_t, uint8_t, uint8_t)> callback)
{ {
Serial.print("Registering callback"); callbacks[callbacks_handler_count++] = callback;
Serial.write(0xFF);
Serial.write(0xFF);
Serial.write(0xFF);
callbacks.push_back(callback);
} }
uint8_t ClimateCard::getType() uint8_t ClimateCard::getType()
@ -202,9 +174,9 @@ void ClimateCard::updateSensor()
room_temperature = ds18b20->getTempC(); room_temperature = ds18b20->getTempC();
break; break;
} }
for (uint8_t i = 0; i < sensor_callbacks.size(); i++) for (const auto& callback : sensor_callbacks)
{ {
sensor_callbacks[i](room_temperature, humidity); callback.second(room_temperature, humidity);
} }
} }
@ -229,14 +201,9 @@ void ClimateCard::updateAirConditioner()
// rmt_write_items(RMT_TX_CHANNEL, items, itemCount, true); // rmt_write_items(RMT_TX_CHANNEL, items, itemCount, true);
// rmt_wait_tx_done(RMT_TX_CHANNEL, portMAX_DELAY); // rmt_wait_tx_done(RMT_TX_CHANNEL, portMAX_DELAY);
// // Publish state // // Publish state
Serial.print("Callbacks: "); for (const auto& callback : callbacks)
Serial.println(callbacks.size());
Serial.write(0xFF);
Serial.write(0xFF);
Serial.write(0xFF);
for (uint8_t i = 0; i < callbacks.size(); i++)
{ {
callbacks[i](this->state.ac_mode, this->state.ac_fan_speed, this->state.ac_temperature); callback.second(this->state.ac_mode, this->state.ac_fan_speed, this->state.ac_temperature);
} }
} }
@ -272,6 +239,15 @@ uint8_t ClimateCard::getFanSpeed()
void ClimateCard::registerSensorCallback(std::function<void(float, float)> callback) void ClimateCard::registerSensorCallback(std::function<void(float, float)> callback)
{ {
sensor_callbacks.push_back(callback); sensor_callbacks[sensor_callbacks_handler_count++] = callback;
} }
void ClimateCard::unregisterChangeCallback(uint8_t handler)
{
callbacks.erase(handler);
}
void ClimateCard::unregisterSensorCallback(uint8_t handler)
{
sensor_callbacks.erase(handler);
}

View File

@ -5,7 +5,7 @@
#include <OneWire.h> #include <OneWire.h>
#include <DS18B20.h> #include <DS18B20.h>
#include <dhtnew.h> #include <dhtnew.h>
#include <vector> #include <map>
#define RMT_TX_CHANNEL RMT_CHANNEL_0 #define RMT_TX_CHANNEL RMT_CHANNEL_0
@ -60,6 +60,8 @@ class ClimateCard : public ExpansionCard {
uint8_t getSensorType(); uint8_t getSensorType();
void registerChangeCallback(std::function<void(uint8_t, uint8_t, uint8_t)> callback); void registerChangeCallback(std::function<void(uint8_t, uint8_t, uint8_t)> callback);
void registerSensorCallback(std::function<void(float, float)> callback); void registerSensorCallback(std::function<void(float, float)> callback);
void unregisterChangeCallback(uint8_t handler);
void unregisterSensorCallback(uint8_t handler);
uint8_t getType(); uint8_t getType();
private: private:
// Sensor objects // Sensor objects
@ -67,8 +69,10 @@ class ClimateCard : public ExpansionCard {
DHTNEW *dht; DHTNEW *dht;
DS18B20 *ds18b20; DS18B20 *ds18b20;
// Callbacks // Callbacks
std::vector<std::function<void(uint8_t, uint8_t, uint8_t)>> callbacks; uint8_t callbacks_handler_count = 0;
std::vector<std::function<void(float, float)>> sensor_callbacks; uint8_t sensor_callbacks_handler_count = 0;
std::map<uint8_t,std::function<void(uint8_t, uint8_t, uint8_t)>> callbacks;
std::map<uint8_t,std::function<void(float, float)>> sensor_callbacks;
// Update functions // Update functions
void updateSensor(); void updateSensor();
void updateAirConditioner(); void updateAirConditioner();

View File

@ -5,6 +5,7 @@ DigitalInputCard::DigitalInputCard(uint8_t address_a, uint8_t address_b) : callb
{ {
this->address_a = address_a; this->address_a = address_a;
this->address_b = address_b; this->address_b = address_b;
this->callbacks_handler_index = 0;
} }
// Instantiate the card with the specified position on the dip switch // Instantiate the card with the specified position on the dip switch
// Bit 0,1,2 are for bank A // Bit 0,1,2 are for bank A
@ -95,8 +96,8 @@ void DigitalInputCard::handlePinChange(int pin, uint8_t &currentBuffer, uint8_t
{ {
lastDebounceTime[pin] = millis(); lastDebounceTime[pin] = millis();
previousBuffer ^= (-((currentBuffer >> (7 - pin)) & 1) ^ previousBuffer) & (1UL << (7 - pin)); previousBuffer ^= (-((currentBuffer >> (7 - pin)) & 1) ^ previousBuffer) & (1UL << (7 - pin));
for (int i = 0; i < callbacks.size(); i++) for(const auto& callback : callbacks)
callbacks[i](virtualPin, ((currentBuffer >> (7 - pin)) & 1)); callback.second(virtualPin, ((currentBuffer >> (7 - pin)) & 1));
} }
} }
// Handle Bank B // Handle Bank B
@ -106,8 +107,8 @@ void DigitalInputCard::handlePinChange(int pin, uint8_t &currentBuffer, uint8_t
{ {
lastDebounceTime[pin] = millis(); lastDebounceTime[pin] = millis();
previousBuffer ^= (-((currentBuffer >> (15 - pin)) & 1) ^ previousBuffer) & (1UL << (15 - pin)); previousBuffer ^= (-((currentBuffer >> (15 - pin)) & 1) ^ previousBuffer) & (1UL << (15 - pin));
for (int i = 0; i < callbacks.size(); i++) for (const auto& callback : callbacks)
callbacks[i](virtualPin, ((currentBuffer >> (15 - pin)) & 1)); callback.second(virtualPin, ((currentBuffer >> (15 - pin)) & 1));
} }
} }
} }
@ -158,9 +159,7 @@ uint8_t DigitalInputCard::getInputBufferB()
// Register a callback function to be called when a pin changes // Register a callback function to be called when a pin changes
void DigitalInputCard::registerCallback(std::function<void(uint8_t, bool)> callback) void DigitalInputCard::registerCallback(std::function<void(uint8_t, bool)> callback)
{ {
ESP_LOGD("DigitalInputCard", "Registering callback"); callbacks[this->callbacks_handler_index++] = callback;
callbacks.push_back(callback);
ESP_LOGD("DigitalInputCard", "Callback registered");
} }
// Refresh the input buffer for bank A // Refresh the input buffer for bank A
@ -180,17 +179,10 @@ void DigitalInputCard::setDebounceTime(uint8_t pin, uint32_t debounceTime)
this->debounceTime[pin] = debounceTime; this->debounceTime[pin] = debounceTime;
} }
// void DigitalInputCard::unregisterCallback(std::function<void(uint8_t, bool)> callback) void DigitalInputCard::unregisterCallback(uint8_t handler)
// { {
// for (int i = 0; i < callbacks.size(); i++) callbacks.erase(handler);
// { }
// if (callbacks[i].target<void(uint8_t, bool)>() == callback.target<void(uint8_t, bool)>())
// {
// callbacks.erase(callbacks.begin() + i);
// break;
// }
// }
// }
void DigitalInputCard::loadPinMap(uint8_t pinMap[16]) void DigitalInputCard::loadPinMap(uint8_t pinMap[16])
{ {

View File

@ -1,7 +1,7 @@
#pragma once #pragma once
#include <ExpansionCard.hpp> #include <ExpansionCard.hpp>
#include <PCF8574.h> #include <PCF8574.h>
#include <vector> #include <map>
#define CARD_TYPE_DIGITAL_INPUT 0x01 #define CARD_TYPE_DIGITAL_INPUT 0x01
@ -28,7 +28,7 @@ class DigitalInputCard : public ExpansionCard {
// Register a callback function to be called when a pin changes // Register a callback function to be called when a pin changes
void registerCallback(std::function<void(uint8_t, bool)> callback); void registerCallback(std::function<void(uint8_t, bool)> callback);
// Unregister the callback function // Unregister the callback function
//void unregisterCallback(std::function<void(uint8_t, bool)> callback); void unregisterCallback(uint8_t handler);
// Load a new pin map // Load a new pin map
void loadPinMap(uint8_t pinMap[16]); void loadPinMap(uint8_t pinMap[16]);
// Get type of card // Get type of card
@ -48,7 +48,8 @@ class DigitalInputCard : public ExpansionCard {
uint8_t pinMap[16]; uint8_t pinMap[16];
// A map of the virtual pin to the physical pin // A map of the virtual pin to the physical pin
uint8_t virtualPinMap[16]; uint8_t virtualPinMap[16];
std::vector<std::function<void(uint8_t, bool)>> callbacks; uint8_t callbacks_handler_index = 0;
std::map<uint8_t, std::function<void(uint8_t, bool)>> callbacks;
void refreshInputBankA(); void refreshInputBankA();
void refreshInputBankB(); void refreshInputBankB();
void handlePinChange(int pin, uint8_t& currentBuffer, uint8_t& previousBuffer); void handlePinChange(int pin, uint8_t& currentBuffer, uint8_t& previousBuffer);

View File

@ -7,16 +7,15 @@ DigitalOutputCard::DigitalOutputCard(uint8_t address) : change_callbacks(){
this->pinMap[i] = i; this->pinMap[i] = i;
this->virtualPinMap[i] = i; this->virtualPinMap[i] = i;
} }
this->framBinded = false;
this->callbacks_handler_index = 0;
} }
// Instantiate the card with the specified position on the dip switch // Instantiate the card with the specified position on the dip switch
DigitalOutputCard::DigitalOutputCard(bool bit0, bool bit1, bool bit2, bool bit3, bool bit4) { DigitalOutputCard::DigitalOutputCard(bool bit0, bool bit1, bool bit2, bool bit3, bool bit4) :
this->address = 0x20; DigitalOutputCard(0x20+bit0+bit1*2+bit2*4+bit3*8+bit4*16)
if (bit0) this->address += 1; {
if (bit1) this->address += 2;
if (bit2) this->address += 4;
if (bit3) this->address += 8;
if (bit4) this->address += 16;
} }
// Initialize the card // Initialize the card
bool DigitalOutputCard::begin() { bool DigitalOutputCard::begin() {
@ -36,8 +35,9 @@ void DigitalOutputCard::digitalWrite(uint8_t pin, bool state) {
this->saveStateToFRAM(); this->saveStateToFRAM();
this->savePinValueToFRAM(pin); this->savePinValueToFRAM(pin);
} }
for (int i = 0; i < change_callbacks.size(); i++) { for (const auto& callback : change_callbacks)
change_callbacks[i](pin, state, state ? 4095 : 0); {
callback.second(pin, state, state ? 4095 : 0);
} }
} }
// Set the output to the specified pwm value // Set the output to the specified pwm value
@ -52,8 +52,9 @@ void DigitalOutputCard::analogWrite(uint8_t pin, uint16_t value) {
} }
this->state_buffer[pin] = value > 0; this->state_buffer[pin] = value > 0;
this->value_buffer[pin] = value; this->value_buffer[pin] = value;
for (int i = 0; i < change_callbacks.size(); i++) { for (const auto& callback : change_callbacks)
change_callbacks[i](pin, value > 0, value); {
callback.second(pin, value > 0, value);
} }
} }
@ -82,8 +83,8 @@ void DigitalOutputCard::setState(uint8_t pin, bool state) {
if(this->framAutoSave) { if(this->framAutoSave) {
this->saveStateToFRAM(); this->saveStateToFRAM();
} }
for(int i = 0; i < change_callbacks.size(); i++) { for(const auto& callback : change_callbacks) {
change_callbacks[i](pin, state, value_buffer[pin]); callback.second(pin, state, value_buffer[pin]);
} }
} }
@ -95,23 +96,19 @@ void DigitalOutputCard::setValue(uint8_t pin, uint16_t value) {
if (this->framAutoSave) { if (this->framAutoSave) {
this->savePinValueToFRAM(pin); this->savePinValueToFRAM(pin);
} }
for (int i = 0; i < change_callbacks.size(); i++) { for (const auto& callback : change_callbacks)
change_callbacks[i](pin, state_buffer[pin], value); {
callback.second(pin, state_buffer[pin], value);
} }
} }
void DigitalOutputCard::registerChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback) { void DigitalOutputCard::registerChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback) {
this->change_callbacks.push_back(callback); this->change_callbacks[this->callbacks_handler_index++] = callback;
} }
// void DigitalOutputCard::deregisterChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback) { void DigitalOutputCard::deregisterChangeCallback(uint8_t handler) {
// for(int i = 0; i < change_callbacks.size(); i++) { this->change_callbacks.erase(handler);
// if(change_callbacks[i].target<void(uint8_t, bool, uint16_t)>() == callback.target<void(uint8_t, bool, uint16_t)>()) { }
// change_callbacks.erase(change_callbacks.begin()+i);
// break;
// }
// }
// }
void DigitalOutputCard::loadPinMap(uint8_t pinMap[16]) { void DigitalOutputCard::loadPinMap(uint8_t pinMap[16]) {
for(int i = 0; i < 16; i++) { for(int i = 0; i < 16; i++) {

View File

@ -2,7 +2,7 @@
#include <ExpansionCard.hpp> #include <ExpansionCard.hpp>
#include <Adafruit_PWMServoDriver.h> #include <Adafruit_PWMServoDriver.h>
#include <FRAM.h> #include <FRAM.h>
#include <vector> #include <map>
// Protocol for digital output card // Protocol for digital output card
// Note that pin is always 2 characters long and padded with 0 if necessary // Note that pin is always 2 characters long and padded with 0 if necessary
@ -50,7 +50,7 @@ public:
// Register a callback function that will be called when the state of a pin changes // Register a callback function that will be called when the state of a pin changes
void registerChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback); void registerChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback);
// Deregister the callback function // Deregister the callback function
// void deregisterChangeCallback(std::function<void(uint8_t, bool, uint16_t)> callback); void deregisterChangeCallback(uint8_t handler);
// Load a new pin map // Load a new pin map
void loadPinMap(uint8_t pinMap[16]); void loadPinMap(uint8_t pinMap[16]);
// Bind the fram object to the card // Bind the fram object to the card
@ -90,7 +90,8 @@ private:
// The pwm value of the card // The pwm value of the card
uint16_t value_buffer[16]; uint16_t value_buffer[16];
// The callback function // The callback function
std::vector<std::function<void(uint8_t, bool, uint16_t)>> change_callbacks; uint8_t callbacks_handler_index = 0;
std::map<uint8_t, std::function<void(uint8_t, bool, uint16_t)>> change_callbacks;
// Physical pin to virtual pin map // Physical pin to virtual pin map
uint8_t pinMap[16]; uint8_t pinMap[16];
// Return 16 bit value representing all 16 channels // Return 16 bit value representing all 16 channels

View File

@ -52,37 +52,37 @@ void setup() {
espmega.enableIotModule(); espmega.enableIotModule();
ETH.begin(); ETH.begin();
espmega.iot->bindEthernetInterface(&ETH); espmega.iot->bindEthernetInterface(&ETH);
NetworkConfig config = { // NetworkConfig config = {
.ip = {192, 168, 0, 11}, // .ip = {192, 168, 0, 11},
.gateway = {192, 168, 0, 1}, // .gateway = {192, 168, 0, 1},
.subnet = {255, 255, 255, 0}, // .subnet = {255, 255, 255, 0},
.dns1 = {192, 168, 0, 1}, // .dns1 = {192, 168, 0, 1},
.dns2 = {192, 168, 0, 1}, // .dns2 = {192, 168, 0, 1},
.useStaticIp = true, // .useStaticIp = true,
.useWifi = false, // .useWifi = false,
.wifiUseAuth = false, // .wifiUseAuth = false,
}; // };
strcpy(config.ssid, "ssid"); // strcpy(config.ssid, "ssid");
strcpy(config.password, "password"); // strcpy(config.password, "password");
strcpy(config.hostname, "espmega"); // strcpy(config.hostname, "espmega");
Serial.println("Setting network config"); // Serial.println("Setting network config");
espmega.iot->setNetworkConfig(config); // espmega.iot->setNetworkConfig(config);
espmega.iot->saveNetworkConfig(); // espmega.iot->saveNetworkConfig();
// espmega.iot->loadNetworkConfig(); espmega.iot->loadNetworkConfig();
Serial.println("Connecting to network"); Serial.println("Connecting to network");
espmega.iot->connectNetwork(); espmega.iot->connectNetwork();
Serial.println("Begin MQTT Modules"); Serial.println("Begin MQTT Modules");
MqttConfig mqtt_config = { // MqttConfig mqtt_config = {
.mqtt_port = 1883, // .mqtt_port = 1883,
.mqtt_useauth = false // .mqtt_useauth = false
}; // };
Serial.println("Setting MQTT Server"); // Serial.println("Setting MQTT Server");
strcpy(mqtt_config.mqtt_server, "192.168.0.26"); // strcpy(mqtt_config.mqtt_server, "192.168.0.26");
strcpy(mqtt_config.base_topic, "/espmegaoop"); // strcpy(mqtt_config.base_topic, "/espmegaoop");
Serial.println("Loading MQTT Config Struct to IoT Module"); // Serial.println("Loading MQTT Config Struct to IoT Module");
espmega.iot->setMqttConfig(mqtt_config); // espmega.iot->setMqttConfig(mqtt_config);
espmega.iot->saveMqttConfig(); // espmega.iot->saveMqttConfig();
// espmega.iot->loadMqttConfig(); espmega.iot->loadMqttConfig();
Serial.println("Connecting to MQTT"); Serial.println("Connecting to MQTT");
espmega.iot->connectToMqtt(); espmega.iot->connectToMqtt();
Serial.println("Registering Output Card"); Serial.println("Registering Output Card");
@ -112,13 +112,13 @@ void setup() {
// Every 20 seconds, dump FRAM 0-500 to serial // Every 20 seconds, dump FRAM 0-500 to serial
void loop() { void loop() {
espmega.loop(); espmega.loop();
static uint32_t last_fram_dump = 0; // static uint32_t last_fram_dump = 0;
if (millis() - last_fram_dump >= 20000) { // if (millis() - last_fram_dump >= 20000) {
last_fram_dump = millis(); // last_fram_dump = millis();
Serial.println("Dumping FRAM"); // Serial.println("Dumping FRAM");
espmega.dumpFRAMtoSerial(0, 500); // espmega.dumpFRAMtoSerial(0, 500);
Serial.println("Dumping FRAM ASCII"); // Serial.println("Dumping FRAM ASCII");
espmega.dumpFRAMtoSerialASCII(0, 500); // espmega.dumpFRAMtoSerialASCII(0, 500);
} // }
} }