Compare commits

..

30 Commits

Author SHA1 Message Date
Siwat Sirichai a056531ab0 Merge branch 'main' into recovery-mode 2024-05-19 03:03:56 +07:00
Siwat Sirichai d75b028cd2 improve MQTT state request 2024-05-17 21:29:50 +07:00
Siwat Sirichai dc96be25b8 update IR Capture 2024-04-04 18:03:34 +07:00
Siwat Sirichai 6ff586b27b Update AnalogCard.cpp 2024-04-01 22:37:20 +07:00
Siwat Sirichai a9871315f2 missing DACs no longer cause analog card to fails 2024-04-01 22:36:53 +07:00
Siwat Sirichai 667823d598 Fix analog bank B not being read 2024-04-01 22:34:40 +07:00
Siwat Sirichai 9344610582 Update ESPMegaDisplay.cpp 2024-03-31 00:07:55 +07:00
Siwat Sirichai e2977c565c fix display update when using different baudrate 2024-03-30 23:59:44 +07:00
Siwat Sirichai 84d20173ac auto init display 2024-03-30 22:41:21 +07:00
Siwat Sirichai 9725a8d867 Merge branch 'main' of https://git.siwatsystem.com/siwat/ESPMegaPRO-v3-SDK 2024-03-30 01:30:03 +07:00
Siwat Sirichai 6e287255c6 add IR code learner 2024-03-29 01:17:54 +07:00
Siwat Sirichai 199a89a700 move ct conversion counter 2024-03-25 14:16:15 +07:00
Siwat Sirichai 3a9488d4f8 fix conversion loop bug 2024-03-25 11:11:50 +07:00
Siwat Sirichai de8672b9cb add MQTT availability topic 2024-03-25 01:27:41 +07:00
Siwat Sirichai b051ba8d90 fix SmartVariable Callback bug 2024-03-23 13:20:34 +07:00
Siwat Sirichai dcc9092026 allow absolute callback inside base topic 2024-03-23 13:12:12 +07:00
Siwat Sirichai 919c28a9c7 change SmartVariable Callback to std::function 2024-03-23 12:38:13 +07:00
Siwat Sirichai 1d977c5bdf working smart variable 2024-03-23 11:54:53 +07:00
Siwat Sirichai 1b2a270d38 Update main.cpp 2024-03-23 10:46:53 +07:00
Siwat Sirichai 7c338324f3 pass compile smart variable 2024-03-23 10:29:04 +07:00
Siwat Sirichai 7f55e3544d smart variable implementation 2024-03-23 10:25:16 +07:00
Siwat Sirichai aa28ec88fb smart variable header 2024-03-23 02:09:50 +07:00
Siwat Sirichai c56a98f823 fix ac load state bug 2024-03-23 01:54:52 +07:00
Siwat Sirichai 62aa76b06a obfuscate passwords 2024-03-20 02:22:34 +07:00
Siwat Sirichai 196a87d47b change analogcard init behavior 2024-03-10 00:57:16 +07:00
Siwat Sirichai 594ea6bf54 CT Card now inherit expansion card 2024-02-27 14:38:15 +07:00
Siwat Sirichai e380606742 optimize climate card 2024-02-16 23:55:43 +07:00
Siwat Sirichai f4af513d65 Merge branch 'main' of https://git.siwatsystem.com/siwat/ESPMegaPRO-v3-SDK 2024-02-16 23:52:07 +07:00
Siwat Sirichai 8988b59103 fix internal display pwm adjustment bug 2024-02-16 01:23:59 +07:00
Siwat Sirichai 1dd0862834 remote var callback docs 2024-02-13 01:00:20 +07:00
26 changed files with 705 additions and 111 deletions

4
.vscode/launch.json vendored
View File

@ -8,8 +8,8 @@
"args": [],
"stopAtEntry": false,
"externalConsole": true,
"cwd": "d:/Git/ESPMegaPRO-v3-SDK/ESPMegaPRO-OS-SDK/lib/ESPMegaPRO",
"program": "d:/Git/ESPMegaPRO-v3-SDK/ESPMegaPRO-OS-SDK/lib/ESPMegaPRO/build/Debug/outDebug",
"cwd": "d:/Git/ESPMegaPRO-v3-SDK/ESPMegaPRO-OS-SDK/src",
"program": "d:/Git/ESPMegaPRO-v3-SDK/ESPMegaPRO-OS-SDK/src/build/Debug/outDebug",
"MIMode": "gdb",
"miDebuggerPath": "gdb",
"setupCommands": [

View File

@ -55,5 +55,9 @@
"C_Cpp_Runner.useLeakSanitizer": false,
"C_Cpp_Runner.showCompilationTime": false,
"C_Cpp_Runner.useLinkTimeOptimization": false,
"C_Cpp_Runner.msvcSecureNoWarnings": false
"C_Cpp_Runner.msvcSecureNoWarnings": false,
"files.associations": {
"istream": "cpp",
"map": "cpp"
}
}

View File

@ -10,37 +10,93 @@
* The first dimension is the temperature, the second dimension is the timing
*/
#define MIN_TEMP 16
#define MAX_TEMP 30
#define min_temp 16
#define max_temp 32
#define MAX_TIMINGS 1000 // 1000 timings should be enough for any remote
#define CAPTURE_TIMEOUT 5 // seconds
uint16_t timings[MAX_TEMP - MIN_TEMP + 1][MAX_TIMINGS] = {0};
uint16_t timings_count[MAX_TEMP - MIN_TEMP + 1] = {0};
uint32_t timings[max_temp - min_temp + 1][MAX_TIMINGS] = {0};
uint16_t timings_count[max_temp - min_temp + 1] = {0};
ESPMegaPRO espmega = ESPMegaPRO();
void beginRoutine()
{
Serial.println("Beginning IR capture routine");
for (int i = MIN_TEMP; i <= MAX_TEMP; i++)
for (int i = min_temp; i <= max_temp; i++)
{
Serial.printf("Please press the button on your remote for %d degrees\n", i);
IRReceiver::start_long_receive();
for (int i = 0; i < CAPTURE_TIMEOUT; i++)
{
Serial.printf("Waiting for IR signal... (%d seconds left)\n", CAPTURE_TIMEOUT - i);
// During this period, if the user press any key, the routine will be restarted
// Unless it is a space bar, which will be used to confirm the timings
if (Serial.available())
{
char c = Serial.read();
if (c != ' ')
{
Serial.println("User interrupted, restarting routine...");
return;
}
}
vTaskDelay(1000 / portTICK_PERIOD_MS);
}
ir_data_t data = IRReceiver::end_long_receive();
timings_count[i - MIN_TEMP] = data.size;
// Retry if no data was received
if (data.size == 0)
{
Serial.println("No data received, retrying...");
i--;
continue;
}
// Remove last timing
data.size--;
Serial.printf("Received timing of size %d\n", data.size);
// Print out the timing array
for (int i = 0; i < data.size; i++)
{
Serial.printf("%u%s", data.data[i], i == data.size - 1 ? "\n" : ", ");
}
// If any timings exceed 20000, print a warning
for (int i = 0; i < data.size; i++)
{
if (data.data[i] > 50000U)
{
Serial.println("WARNING: Timing exceeds 50000, Possible data corruption!");
break;
}
}
// Ask the user if the timings are correct
Serial.println("Are the timings correct? (y/n)");
// Flush the serial buffer
while (Serial.available())
{
Serial.read();
}
// Wait for user input
while (!Serial.available())
{
vTaskDelay(100 / portTICK_PERIOD_MS);
}
char c = Serial.read();
if (c != 'y')
{
Serial.println("Retrying...");
i--;
continue;
}
// Store the timings count
timings_count[i - min_temp] = data.size;
// Copy the timings into the timings array
memcpy(timings[i - MIN_TEMP], data.data, sizeof(uint16_t) * data.size);
memcpy(timings[i - min_temp], data.data, sizeof(uint32_t) * data.size);
free(data.data);
}
Serial.println("Generating C++ code for the timings, please wait...");
// Find the maximum number of timings
int max_timings = 0;
for (int i = 0; i < MAX_TEMP - MIN_TEMP + 1; i++)
for (int i = 0; i < max_temp - min_temp + 1; i++)
{
if (timings_count[i] > max_timings)
{
@ -49,27 +105,114 @@ void beginRoutine()
}
// Print the timings
Serial.println("Done!, please copy the following into your main program");
Serial.printf("uint16_t timings[%d][%d] = {\n", MAX_TEMP - MIN_TEMP + 1, max_timings);
for (int i = 0; i < MAX_TEMP - MIN_TEMP + 1; i++)
Serial.printf("uint16_t timings[%d][%d] = {\n", max_temp - min_temp + 1, max_timings);
for (int i = 0; i < max_temp - min_temp + 1; i++)
{
Serial.printf(" {");
for (int j = 0; j < timings_count[i]; j++)
{
Serial.printf("%d%s", timings[i][j], j == timings_count[i] - 1 ? "" : ", ");
Serial.printf("%u%s", timings[i][j], j == timings_count[i] - 1 ? "" : ", ");
}
Serial.println(i == MAX_TEMP - MIN_TEMP ? "}" : "},");
Serial.println(i == max_temp - min_temp ? "}" : "},");
}
Serial.println("};");
Serial.println("Stopping IR capture routine");
Serial.printf("IR Capture routine finished\n");
}
void capture_single()
{
Serial.println("Please press the button on your remote");
IRReceiver::start_long_receive();
for (int i = 0; i < CAPTURE_TIMEOUT; i++)
{
Serial.printf("Waiting for IR signal... (%d seconds left)\n", CAPTURE_TIMEOUT - i);
vTaskDelay(1000 / portTICK_PERIOD_MS);
}
ir_data_t data = IRReceiver::end_long_receive();
// Remove last timing
data.size--;
Serial.printf("Received timing of size %d\n", data.size);
// If any timings exceed 20000, print a warning
for (int i = 0; i < data.size; i++)
{
if (data.data[i] > 50000U)
{
Serial.println("WARNING: Timing exceeds 50000, Possible data corruption!");
break;
}
}
if (data.size == 0)
{
Serial.println("No data received, retrying...");
capture_single();
return;
}
// Print the timings
Serial.println("Done!, please copy the following into your main program");
Serial.printf("uint32_t timings[%d] = {", data.size);
for (int i = 0; i < data.size; i++)
{
Serial.printf("%u%s", data.data[i], i == data.size - 1 ? "" : ", ");
}
Serial.println("};");
free(data.data);
Serial.println("Do you want to capture another signal? (y/n)");
// Flush the serial buffer
while (Serial.available())
{
Serial.read();
}
// Wait for user input
while (!Serial.available())
{
vTaskDelay(100 / portTICK_PERIOD_MS);
}
char c = Serial.read();
if (c == 'y')
{
capture_single();
}
}
void menu_init()
{
// Print the menu
// The menu will have 2 options, one to start the routine, and one capture a single IR signal
Serial.println("ESPMegaPRO IR Development Kit - IR Capture");
Serial.println("1. Begin IR Capture Routine");
Serial.println("2. Capture Single IR Signal");
Serial.println("Please select an option:");
// Wait for user input
while (!Serial.available())
{
vTaskDelay(100 / portTICK_PERIOD_MS);
}
char c = Serial.read();
// Start the routine
if (c == '1')
{
beginRoutine();
}
// Capture a single IR signal
else if (c == '2')
{
capture_single();
}
}
void setup()
{
IRReceiver::begin(17);
IRReceiver::begin(36);
espmega.begin();
}
void loop()
{
beginRoutine();
delay(10000);
menu_init();
Serial.println("Press any key to return to the main menu");
while (!Serial.available())
{
vTaskDelay(100 / portTICK_PERIOD_MS);
}
}

View File

@ -133,37 +133,38 @@ uint16_t AnalogCard::analogRead(uint8_t pin)
*/
bool AnalogCard::begin()
{
bool success = true;
if (!this->dac0.begin())
{
ESP_LOGE("AnalogCard", "Card Analog ERROR: Failed to install DAC0");
return false;
// success = false;
}
if (!this->dac1.begin())
{
ESP_LOGE("AnalogCard", "Card Analog ERROR: Failed to install DAC1");
return false;
// success = false;
}
if (!this->dac2.begin())
{
ESP_LOGE("AnalogCard", "Card Analog ERROR: Failed to install DAC2");
return false;
// success = false;
}
if (!this->dac3.begin())
{
ESP_LOGE("AnalogCard", "Card Analog ERROR: Failed to install DAC3");
return false;
// success = false;
}
if (!this->analogInputBankA.begin())
if (!this->analogInputBankA.begin(ANALOG_INPUT_BANK_A_ADDRESS))
{
ESP_LOGE("AnalogCard", "Card Analog ERROR: Failed to install analog input bank A");
return false;
success = false;
}
if (!this->analogInputBankB.begin())
if (!this->analogInputBankB.begin(ANALOG_INPUT_BANK_B_ADDRESS))
{
ESP_LOGE("AnalogCard", "Card Analog ERROR: Failed to install analog input bank B");
return false;
success = false;
}
return true;
return success;
}
/**

View File

@ -152,6 +152,10 @@ void ClimateCard::loadStateFromFRAM()
{
if (fram == nullptr)
return;
// Retrieve state from FRAM
state.ac_temperature = fram->read8(fram_address);
state.ac_mode = fram->read8(fram_address + 1);
state.ac_fan_speed = fram->read8(fram_address + 2);
if (state.ac_temperature > ac.max_temperature)
state.ac_temperature = ac.max_temperature;
else if (state.ac_temperature < ac.min_temperature)
@ -345,7 +349,6 @@ void ClimateCard::updateSensor()
*/
void ClimateCard::updateAirConditioner()
{
// // The IR Transmissions are not working yet so we just return
const uint16_t* ir_code_ptr = nullptr;
size_t itemCount = (*(this->ac.getInfraredCode))(this->state.ac_mode, this->state.ac_fan_speed, this->state.ac_temperature-this->ac.min_temperature, &ir_code_ptr);
@ -452,4 +455,14 @@ void ClimateCard::unregisterChangeCallback(uint8_t handler)
void ClimateCard::unregisterSensorCallback(uint8_t handler)
{
sensor_callbacks.erase(handler);
}
void ClimateCard::setState(uint8_t mode, uint8_t fan_speed, uint8_t temperature)
{
this->state.ac_mode = mode;
this->state.ac_fan_speed = fan_speed;
this->state.ac_temperature = temperature;
updateAirConditioner();
if (fram_auto_save)
saveStateToFRAM();
}

View File

@ -81,6 +81,7 @@ class ClimateCard : public ExpansionCard {
void setFanSpeed(uint8_t fan_speed);
void setFanSpeedByName(const char* fan_speed_name);
uint8_t getFanSpeed();
void setState(uint8_t mode, uint8_t fan_speed, uint8_t temperature);
char* getFanSpeedName();
float getRoomTemperature();
float getHumidity();

View File

@ -148,6 +148,7 @@ void ClimateIoT::subscribe() {
this->subscribeRelative(AC_TEMPERATURE_SET_TOPIC);
this->subscribeRelative(AC_MODE_SET_TOPIC);
this->subscribeRelative(AC_FAN_SPEED_SET_TOPIC);
this->subscribeRelative(AC_REQUEST_STATE_TOPIC);
ESP_LOGD("ClimateIoT", "Subscribed to topics");
}

View File

@ -12,7 +12,7 @@
#define AC_FAN_SPEED_SET_TOPIC "set/fan_speed"
#define AC_ROOM_TEMPERATURE_REPORT_TOPIC "room_temperature"
#define AC_HUMIDITY_REPORT_TOPIC "humidity"
#define AC_REQUEST_STATE_TOPIC "request_state"
#define AC_REQUEST_STATE_TOPIC "requeststate"
/**
* @brief The ClimateIoT class is a class for connecting the Climate Card to the IoT module.

View File

@ -6,6 +6,7 @@ CurrentTransformerCard::CurrentTransformerCard(AnalogCard* analogCard, uint8_t p
this->pin = pin;
this->voltage = voltage;
this->adcToCurrent = adcToCurrent;
this->conversionInterval = conversionInterval;
}
void CurrentTransformerCard::bindFRAM(FRAM *fram, uint32_t framAddress)
@ -14,9 +15,14 @@ void CurrentTransformerCard::bindFRAM(FRAM *fram, uint32_t framAddress)
this->framAddress = framAddress;
}
void CurrentTransformerCard::begin()
bool CurrentTransformerCard::begin()
{
// Is analogCard a nullptr?
if (this->analogCard == nullptr) {
return false;
}
this->beginConversion();
return true;
}
void CurrentTransformerCard::loop()
@ -24,7 +30,7 @@ void CurrentTransformerCard::loop()
if (this->lastConversionTime == 0) {
this->lastConversionTime = millis();
}
static uint32_t lastConversionLoopTime = 0;
if (millis() - lastConversionLoopTime > this->conversionInterval) {
this->beginConversion();
lastConversionLoopTime = millis();

View File

@ -1,5 +1,6 @@
#pragma once
#include <AnalogCard.hpp>
#include <ExpansionCard.hpp>
#include <FRAM.h>
#include <map>
@ -10,12 +11,12 @@
* Also supports storing energy to FRAM.
*/
class CurrentTransformerCard
class CurrentTransformerCard : public ExpansionCard
{
public:
CurrentTransformerCard(AnalogCard* analogCard, uint8_t pin, float *voltage, std::function<float(uint16_t)> adcToCurrent, uint32_t conversionInterval);
void bindFRAM(FRAM *fram, uint32_t framAddress); // Takes 16 bytes of FRAM (long double energy)
void begin();
bool begin();
void loop();
void beginConversion();
void setEnergy(float energy);
@ -45,5 +46,6 @@ class CurrentTransformerCard
std::function<float(uint16_t)> adcToCurrent; // std::function that convert adc value to current in amps
uint8_t handler_count = 0;
std::map<uint8_t,std::function<void(float, double)>> callbacks;
uint32_t lastConversionLoopTime;
};

View File

@ -31,6 +31,7 @@ bool DigitalInputIoT::begin(uint8_t card_id, ExpansionCard *card, PubSubClient *
*/
void DigitalInputIoT::subscribe() {
this->subscribeRelative(PUBLISH_ENABLE_TOPIC);
this->subscribeRelative(INPUT_REQUEST_STATE_TOPIC);
}
/**
@ -40,14 +41,18 @@ void DigitalInputIoT::subscribe() {
* @param payload The null-terminated payload of the MQTT message.
*/
void DigitalInputIoT::handleMqttMessage(char *topic, char *payload) {
if (!strcmp(topic, INPUT_REQUEST_STATE_TOPIC)) {
this->publishDigitalInputs();
}
// payload is char '0' or '1'
if (!strcmp(topic, PUBLISH_ENABLE_TOPIC)) {
else if (!strcmp(topic, PUBLISH_ENABLE_TOPIC)) {
if (payload[0] == '1') {
this->setDigitalInputsPublishEnabled(true);
} else {
this->setDigitalInputsPublishEnabled(false);
}
}
}
/**

View File

@ -6,6 +6,7 @@
// MQTT Topics
#define PUBLISH_ENABLE_TOPIC "publish_enable"
#define INPUT_REQUEST_STATE_TOPIC "requeststate"
/**
* @brief The DigitalInputIoT class is a class for connecting the Digital Input Card to the IoT module.

View File

@ -507,7 +507,7 @@ void ESPMegaDisplay::reset()
* @brief Constructor for the ESPMegaDisplay class.
* @param displayAdapter The serial adapter connected to the display.
*/
ESPMegaDisplay::ESPMegaDisplay(HardwareSerial *displayAdapter, uint16_t baudRate, uint16_t uploadBaudRate, uint8_t txPin, uint8_t rxPin)
ESPMegaDisplay::ESPMegaDisplay(HardwareSerial *displayAdapter, uint32_t baudRate, uint32_t uploadBaudRate, uint8_t txPin, uint8_t rxPin)
{
this->baudRate = baudRate;
this->uploadBaudRate = uploadBaudRate;
@ -638,7 +638,7 @@ bool ESPMegaDisplay::beginUpdate(size_t size)
{
// The display's baudrate might be stuck at 9600 if the display is not initialized
// We try to initiate the display at the user specified baud rate first, if it fails, we try again at 9600
if (!beginUpdate(size, uploadBaudRate))
if (!beginUpdate(size, baudRate))
{
ESP_LOGW("ESPMegaDisplay", "Failed to initiate LCD update at %d baud, retrying at 9600 baud.", uploadBaudRate);
if (!beginUpdate(size, 9600))
@ -657,7 +657,7 @@ bool ESPMegaDisplay::beginUpdate(size_t size)
* @note The baud rate that is used to transfer the data is defined by the uploadBaudRate parameter in the constructor.
* @return True if the OTA update is started, false otherwise.
*/
bool ESPMegaDisplay::beginUpdate(size_t size, uint16_t baudRate)
bool ESPMegaDisplay::beginUpdate(size_t size, uint32_t baudRate)
{
if (xSemaphoreTake(this->serialMutex, DISPLAY_MUTEX_TAKE_TIMEOUT) == pdFALSE)
{
@ -765,7 +765,7 @@ void ESPMegaDisplay::endUpdate()
xSemaphoreGive(this->serialMutex);
this->reset();
delay(500);
this->begin();
esp_restart();
}
/**

View File

@ -17,7 +17,7 @@
class ESPMegaDisplay
{
public:
ESPMegaDisplay(HardwareSerial *displayAdapter, uint16_t baudRate, uint16_t uploadBaudRate, uint8_t txPin, uint8_t rxPin);
ESPMegaDisplay(HardwareSerial *displayAdapter, uint32_t baudRate, uint32_t uploadBaudRate, uint8_t txPin, uint8_t rxPin);
void begin();
void loop();
void reset();
@ -39,13 +39,13 @@ class ESPMegaDisplay
void giveSerialMutex();
SemaphoreHandle_t serialMutex;
bool beginUpdate(size_t size);
bool beginUpdate(size_t size, uint16_t baudRate);
bool beginUpdate(size_t size, uint32_t baudRate);
bool writeUpdate(uint8_t* data, size_t size);
void endUpdate();
size_t getUpdateBytesWritten();
protected:
uint16_t baudRate;
uint16_t uploadBaudRate;
uint32_t baudRate;
uint32_t uploadBaudRate;
uint8_t txPin;
uint8_t rxPin;
size_t otaBytesWritten;

View File

@ -3,7 +3,7 @@
/**
* @brief Create a new ESPMegaIoT object
*
*
* @note You shold not create this object directly, Instead, you should use the ESPMegaPRO::iot object
*/
ESPMegaIoT::ESPMegaIoT() : mqtt(tcpClient)
@ -27,11 +27,11 @@ ESPMegaIoT::~ESPMegaIoT()
/**
* @brief The mqtt callback function, This function is called when a message is received on a subscribed topic
*
*
* This function is called when a message is received on a subscribed topic
* The payload is copied to a buffer and a null terminator is added
* The payload is then passed to the respective card's mqtt callback
*
*
* @param topic The topic of the message
* @param payload The payload of the message in byte form
* @param length The length of the payload
@ -42,12 +42,12 @@ void ESPMegaIoT::mqttCallback(char *topic, byte *payload, unsigned int length)
memcpy(payload_buffer, payload, length);
payload_buffer[length] = '\0';
// If the topic is not appended with the base topic, call only the absolute callbacks
for (const auto &callback : mqtt_callbacks)
{
callback.second(topic, payload_buffer);
}
if (strncmp(topic, this->mqtt_config.base_topic, base_topic_length) != 0)
{
for (const auto &callback : mqtt_callbacks)
{
callback.second(topic, payload_buffer);
}
return;
}
// Remove the base topic from the topic
@ -72,7 +72,7 @@ void ESPMegaIoT::mqttCallback(char *topic, byte *payload, unsigned int length)
/**
* @brief Set the base topic for the IoT
*
*
* @param base_topic The base topic
*/
void ESPMegaIoT::setBaseTopic(char *base_topic)
@ -83,7 +83,7 @@ void ESPMegaIoT::setBaseTopic(char *base_topic)
/**
* @brief Begin the ESPMegaIoT object
*
*
* @param cards The array of ExpansionCard objects
*/
void ESPMegaIoT::intr_begin(ExpansionCard *cards[])
@ -94,7 +94,7 @@ void ESPMegaIoT::intr_begin(ExpansionCard *cards[])
/**
* @brief The main loop for the ESPMegaIoT object
*
*
* @note Normally you should not call this function, Instead, you should call ESPMegaPRO::loop()
*/
void ESPMegaIoT::loop()
@ -115,10 +115,10 @@ void ESPMegaIoT::loop()
/**
* @brief Register an existing card for use with IoT
*
*
* This function registers an existing card for use with IoT
* The card should be installed using ESPMegaPRO::installCard() before calling this function
*
*
* @param card_id The id of the card
*/
void ESPMegaIoT::registerCard(uint8_t card_id)
@ -185,7 +185,7 @@ void ESPMegaIoT::registerCard(uint8_t card_id)
/**
* @brief Unregister a card
*
*
* @param card_id The id of the card
*/
void ESPMegaIoT::unregisterCard(uint8_t card_id)
@ -216,7 +216,7 @@ void ESPMegaIoT::publishCard(uint8_t card_id)
/**
* @brief Subscribe to a topic
*
*
* @param topic The topic to subscribe to
*/
void ESPMegaIoT::subscribe(const char *topic)
@ -226,7 +226,7 @@ void ESPMegaIoT::subscribe(const char *topic)
/**
* @brief Unsubscribe from a topic
*
*
* @param topic The topic to unsubscribe from
*/
void ESPMegaIoT::unsubscribeFromTopic(const char *topic)
@ -236,7 +236,7 @@ void ESPMegaIoT::unsubscribeFromTopic(const char *topic)
/**
* @brief Connect to a wifi network
*
*
* @param ssid The SSID of the wifi network
* @param password The password of the wifi network
*/
@ -247,7 +247,7 @@ void ESPMegaIoT::connectToWifi(const char *ssid, const char *password)
/**
* @brief Connect to a unsecured wifi network
*
*
* @param ssid The SSID of the wifi network
*/
void ESPMegaIoT::connectToWifi(const char *ssid)
@ -265,7 +265,7 @@ void ESPMegaIoT::disconnectFromWifi()
/**
* @brief Check if the wifi is connected
*
*
* @return True if the wifi is connected, false otherwise
*/
bool ESPMegaIoT::wifiConnected()
@ -275,7 +275,7 @@ bool ESPMegaIoT::wifiConnected()
/**
* @brief Connect to a MQTT broker with authentication
*
*
* @param client_id The client id to use
* @param mqtt_server The MQTT server to connect to
* @param mqtt_port The MQTT port to connect to
@ -294,7 +294,10 @@ bool ESPMegaIoT::connectToMqtt(char *client_id, char *mqtt_server, uint16_t mqtt
ESP_LOGE("ESPMegaIoT", "MQTT Connection failed: Username or password not set but MQTT use_auth is true");
return false;
}
if (mqtt.connect(client_id, mqtt_user, mqtt_password))
// Create availability topic
char availability_topic[base_topic_length + 15];
sprintf(availability_topic, "%s/availability", this->mqtt_config.base_topic);
if (mqtt.connect(client_id, mqtt_user, mqtt_password, availability_topic, 0, true, "offline"))
{
sessionKeepAlive();
mqttSubscribe();
@ -307,6 +310,7 @@ bool ESPMegaIoT::connectToMqtt(char *client_id, char *mqtt_server, uint16_t mqtt
}
}
mqtt_connected = true;
mqtt.publish(availability_topic, "online", true);
return true;
}
mqtt_connected = false;
@ -315,7 +319,7 @@ bool ESPMegaIoT::connectToMqtt(char *client_id, char *mqtt_server, uint16_t mqtt
/**
* @brief Connect to a MQTT broker without authentication
*
*
* @param client_id The client id to use
* @param mqtt_server The MQTT server to connect to
* @param mqtt_port The MQTT port to connect to
@ -328,7 +332,10 @@ bool ESPMegaIoT::connectToMqtt(char *client_id, char *mqtt_server, uint16_t mqtt
auto boundCallback = std::bind(&ESPMegaIoT::mqttCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
ESP_LOGD("ESPMegaIoT", "Binding MQTT callback");
mqtt.setCallback(boundCallback);
if (mqtt.connect(client_id))
// Create availability topic
char availability_topic[base_topic_length + 15];
sprintf(availability_topic, "%s/availability", this->mqtt_config.base_topic);
if (mqtt.connect(client_id, availability_topic, 0, true, "offline"))
{
ESP_LOGD("ESPMegaIoT", "MQTT Connected, Calling session keep alive");
sessionKeepAlive();
@ -345,6 +352,7 @@ bool ESPMegaIoT::connectToMqtt(char *client_id, char *mqtt_server, uint16_t mqtt
}
ESP_LOGI("ESPMegaIoT", "MQTT Connected OK.");
mqtt_connected = true;
mqtt.publish(availability_topic, "online", true);
return true;
}
ESP_LOGW("ESPMegaIoT", "MQTT Connection failed: %d", mqtt.state());
@ -362,7 +370,7 @@ void ESPMegaIoT::disconnectFromMqtt()
/**
* @brief Publish a message to a topic
*
*
* @param topic The topic to publish to
* @param payload The payload to publish
*/
@ -373,7 +381,7 @@ void ESPMegaIoT::publish(const char *topic, const char *payload)
/**
* @brief Register a callback for MQTT messages
*
*
* @param callback The callback function
* @return The handler for the callback
*/
@ -385,7 +393,7 @@ uint16_t ESPMegaIoT::registerMqttCallback(std::function<void(char *, char *)> ca
/**
* @brief Unregister a callback
*
*
* @param handler The handler of the callback
*/
void ESPMegaIoT::unregisterMqttCallback(uint16_t handler)
@ -409,7 +417,7 @@ void ESPMegaIoT::mqttSubscribe()
{
if (components[i] != NULL)
{
ESP_LOGD("ESPMegaIoT","Subscribing component %d", i);
ESP_LOGD("ESPMegaIoT", "Subscribing component %d", i);
components[i]->subscribe();
mqtt.loop();
}
@ -473,9 +481,9 @@ void ESPMegaIoT::sessionKeepAlive()
/**
* @brief Register a callback for MQTT messages relative to the base topic
*
*
* The message's base topic will be removed before calling the callback
*
*
* @param callback The callback function
* @return The handler for the callback
*/
@ -487,7 +495,7 @@ uint16_t ESPMegaIoT::registerRelativeMqttCallback(std::function<void(char *, cha
/**
* @brief Unregister a relative MQTT callback
*
*
* @param handler The handler of the callback
*/
void ESPMegaIoT::unregisterRelativeMqttCallback(uint16_t handler)
@ -497,7 +505,7 @@ void ESPMegaIoT::unregisterRelativeMqttCallback(uint16_t handler)
/**
* @brief Publish a message relative to the base topic
*
*
* @param topic The topic to publish to
* @param payload The payload to publish
*/
@ -511,7 +519,7 @@ void ESPMegaIoT::publishRelative(const char *topic, const char *payload)
/**
* @brief Subscribe to a topic relative to the base topic
*
*
* @param topic The topic to subscribe to
*/
void ESPMegaIoT::subscribeRelative(const char *topic)
@ -524,7 +532,7 @@ void ESPMegaIoT::subscribeRelative(const char *topic)
/**
* @brief Register a function to be called when the ESPMegaIoT object is subscribing to topics
*
*
* @param callback The callback function
* @return The handler for the callback
*/
@ -536,7 +544,7 @@ uint16_t ESPMegaIoT::registerSubscribeCallback(std::function<void(void)> callbac
/**
* @brief Unregister a subscribe callback
*
*
* @param handler The handler of the callback
*/
void ESPMegaIoT::unregisterSubscribeCallback(uint16_t handler)
@ -546,7 +554,7 @@ void ESPMegaIoT::unregisterSubscribeCallback(uint16_t handler)
/**
* @brief Set the network config
*
*
* @param network_config The network config struct
*/
void ESPMegaIoT::setNetworkConfig(NetworkConfig network_config)
@ -672,7 +680,7 @@ void ESPMegaIoT::connectNetwork()
/**
* @brief Set the MQTT config
*
*
* @param mqtt_config The MQTT config struct
*/
void ESPMegaIoT::setMqttConfig(MqttConfig mqtt_config)
@ -683,7 +691,7 @@ void ESPMegaIoT::setMqttConfig(MqttConfig mqtt_config)
/**
* @brief Bind an ethernet interface to the ESPMegaIoT object
*
*
* @param ethernetIface The ethernet interface to bind (ETH for ESPMegaPRO R3)
*/
void ESPMegaIoT::bindEthernetInterface(ETHClass *ethernetIface)
@ -693,7 +701,7 @@ void ESPMegaIoT::bindEthernetInterface(ETHClass *ethernetIface)
/**
* @brief Get the IoTComponent object for a card
*
*
* @param card_id The id of the card
* @return The IoTComponent object for the card
*/
@ -704,9 +712,9 @@ IoTComponent *ESPMegaIoT::getComponent(uint8_t card_id)
/**
* @brief Get the network config
*
*
* @warning You should not modify the returned struct directly
*
*
* @return The network config struct
*/
NetworkConfig *ESPMegaIoT::getNetworkConfig()
@ -716,9 +724,9 @@ NetworkConfig *ESPMegaIoT::getNetworkConfig()
/**
* @brief Get the MQTT config
*
*
* @warning You should not modify the returned struct directly
*
*
* @return The MQTT config struct
*/
MqttConfig *ESPMegaIoT::getMqttConfig()
@ -728,18 +736,18 @@ MqttConfig *ESPMegaIoT::getMqttConfig()
/**
* @brief Check if the MQTT is connected
*
*
* @return True if the MQTT is connected, false otherwise
*/
bool ESPMegaIoT::mqttConnected()
{
//return mqtt_connected;
// return mqtt_connected;
return mqtt.connected();
}
/**
* @brief Check if the network is connected
*
*
* @return True if the network is connected, false otherwise
*/
bool ESPMegaIoT::networkConnected()
@ -753,7 +761,7 @@ bool ESPMegaIoT::networkConnected()
/**
* @brief Bind a FRAM object to the ESPMegaIoT object
* @note This class is hardcode to use the FRAM address 34-300
*
*
* @param fram The FRAM object to bind
*/
void ESPMegaIoT::bindFRAM(FRAM *fram)
@ -766,25 +774,28 @@ void ESPMegaIoT::bindFRAM(FRAM *fram)
*
* @return The Wifi IP address
*/
IPAddress ESPMegaIoT::getWifiIp() {
IPAddress ESPMegaIoT::getWifiIp()
{
return WiFi.localIP();
}
/**
* @brief Get the Ethernet IP Address
*
*
* @return The Ethernet IP Address
*/
IPAddress ESPMegaIoT::getETHIp() {
IPAddress ESPMegaIoT::getETHIp()
{
return ETH.localIP();
}
/**
* @brief Get the IP address of the currently active network interface
*
*
* @return The IP address of the currently active network interface
*/
IPAddress ESPMegaIoT::getIp() {
IPAddress ESPMegaIoT::getIp()
{
if (network_config.useWifi)
return this->getWifiIp();
else
@ -793,28 +804,31 @@ IPAddress ESPMegaIoT::getIp() {
/**
* @brief Get the MAC Address of the Ethernet interface
*
*
* @return The MAC Address of the Ethernet interface
*/
String ESPMegaIoT::getETHMac() {
String ESPMegaIoT::getETHMac()
{
return ETH.macAddress();
}
/**
* @brief Get the MAC Address of the Wifi interface
*
*
* @return The MAC Address of the Wifi interface
*/
String ESPMegaIoT::getWifiMac() {
String ESPMegaIoT::getWifiMac()
{
return WiFi.macAddress();
}
/**
* @brief Get the MAC Address of the currently active network interface
*
*
* @return The MAC Address of the currently active network interface
*/
String ESPMegaIoT::getMac() {
String ESPMegaIoT::getMac()
{
if (network_config.useWifi)
return this->getWifiMac();
else

View File

@ -32,7 +32,7 @@ void IRBlaster::send(const uint16_t *data, const size_t size)
items[j].duration1 = 0;
}
}
ESP_ERROR_CHECK(rmt_write_items(channel, items, size / 2 + size % 2, true));
ESP_ERROR_CHECK(rmt_write_items(channel, items, size / 2 + size % 2, false));
delete[] items;
}

View File

@ -17,6 +17,8 @@ void InternalDisplay::begin(ESPMegaIoT *iot, std::function<rtctime_t()> getRtcTi
// Register callbacks
auto bindedPageChangeCallback = std::bind(&InternalDisplay::handlePageChange, this, std::placeholders::_1);
this->registerPageChangeCallback(bindedPageChangeCallback);
auto bindedPayloadCallback = std::bind(&InternalDisplay::handlePayload, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
this->registerPayloadCallback(bindedPayloadCallback);
auto bindedTouchCallback = std::bind(&InternalDisplay::handleTouch, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
this->registerTouchCallback(bindedTouchCallback);
// Initialize the display
@ -212,9 +214,17 @@ void InternalDisplay::saveMQTTConfig()
if (!this->getStringToBuffer("user_set.txt", this->mqttConfig->mqtt_user, 16))
return;
// Save the mqtt password
if (!this->getStringToBuffer("password_set.txt", this->mqttConfig->mqtt_password, 16))
// Check if the password should be
char password_temp[32];
// Get the passwords
if (!this->getStringToBuffer("password_set.txt", password_temp, 16))
return;
// Check if the password should be updated
if (strcmp(password_temp, PASSWORD_OBFUSCATION_STRING))
{
strcpy(this->mqttConfig->mqtt_password, password_temp);
}
// Save the mqtt base topic
if (!this->getStringToBuffer("topic_set.txt", this->mqttConfig->base_topic, 16))
@ -608,6 +618,7 @@ void InternalDisplay::refreshPWMAdjustmentId()
this->displayAdapter->print(pmwAdjustmentPin);
this->displayAdapter->print("\"");
this->sendStopBytes();
this->giveSerialMutex();
}
/**
@ -851,7 +862,7 @@ void InternalDisplay::refreshMQTTConfig()
this->sendStopBytes();
// Refresh the mqtt password
this->displayAdapter->print("password_set.txt=\"");
this->displayAdapter->print(this->mqttConfig->mqtt_password);
this->displayAdapter->print(PASSWORD_OBFUSCATION_STRING);
this->displayAdapter->print("\"");
this->sendStopBytes();
// Refresh the mqtt base topic
@ -919,4 +930,14 @@ void InternalDisplay::setBootStatus(const char *text)
this->displayAdapter->print("\"");
this->sendStopBytes();
this->giveSerialMutex();
}
void InternalDisplay::handlePayload(uint8_t type, uint8_t *payload, uint8_t length) {
// If payload of type 0x92 is received
// Send the display to page 1
if (type == 0x92)
{
this->jumpToPage(1);
}
}

View File

@ -6,6 +6,9 @@
#include <DigitalOutputCard.hpp>
#include <ClimateCard.hpp>
// Password Obfuscation
#define PASSWORD_OBFUSCATION_STRING "********"
// Page IDs
#define INTERNAL_DISPLAY_BOOT_PAGE 0
#define INTERNAL_DISPLAY_DASHBOARD_PAGE 1
@ -101,6 +104,7 @@ class InternalDisplay : public ESPMegaDisplay {
void handleInputStateChange(uint8_t pin, bool state);
void handlePwmStateChange(uint8_t pin, bool state, uint16_t value);
void handlePageChange(uint8_t page);
void handlePayload(uint8_t type, uint8_t *payload, uint8_t length);
void setOutputBar(uint8_t pin, uint16_t value);
void setOutputStateColor(uint8_t pin, bool state);
void setInputMarker(uint8_t pin, bool state);

View File

@ -0,0 +1,184 @@
#include "SmartVariable.hpp"
SmartVariable::SmartVariable()
{
}
SmartVariable::~SmartVariable()
{
if (this->value != nullptr)
free(this->value);
}
void SmartVariable::begin(size_t size)
{
this->value = (char *)calloc(size, sizeof(char));
this->size = size;
}
void SmartVariable::enableIoT(ESPMegaIoT *iot, const char *topic)
{
this->iot = iot;
this->iotEnabled = true;
this->topic = topic;
ESP_LOGV("SmartVariable", "Binding MQTT Callback");
auto bindedMqttCallback = std::bind(&SmartVariable::handleMqttCallback, this, std::placeholders::_1, std::placeholders::_2);
this->iot->registerMqttCallback(bindedMqttCallback);
ESP_LOGV("SmartVariable", "Binding MQTT Subscription");
auto bindedMqttSubscription = std::bind(&SmartVariable::subscribeMqtt, this);
this->iot->registerSubscribeCallback(bindedMqttSubscription);
ESP_LOGI("SmartVariable", "Calling MQTT Subscribe");
this->subscribeMqtt();
}
void SmartVariable::enableValueRequest(const char *valueRequestTopic)
{
ESP_LOGD("SmartVariable", "Enabling Value Request");
this->useValueRequest = true;
this->valueRequestTopic = valueRequestTopic;
this->subscribeMqtt();
}
void SmartVariable::setValue(const char *value)
{
strncpy(this->value, value, this->size - 1);
this->value[this->size - 1] = '\0';
if (this->autoSave)
this->saveValue();
if (this->iotEnabled)
this->publishValue();
// Call Callbacks
for (auto const &callback : this->valueChangeCallbacks)
{
callback.second(this->value);
}
}
char *SmartVariable::getValue()
{
return this->value;
}
void SmartVariable::enableSetValue(const char *setValueTopic)
{
this->setValueEnabled = true;
this->setValueTopic = setValueTopic;
this->subscribeMqtt();
}
void SmartVariable::publishValue()
{
if (this->iotEnabled) {
if (this->value == nullptr) {
ESP_LOGE("SmartVariable", "Value is NULL");
return;
}
if (this->topic == nullptr) {
ESP_LOGE("SmartVariable", "Topic is NULL");
return;
}
ESP_LOGV("SmartVariable", "Publishing Value: %s to %s", this->value, this->topic);
this->iot->publish(this->topic, this->value);
}
}
void SmartVariable::bindFRAM(FRAM *fram, uint32_t framAddress)
{
this->bindFRAM(fram, framAddress, true);
}
void SmartVariable::bindFRAM(FRAM *fram, uint32_t framAddress, bool loadValue)
{
this->framAddress = framAddress;
this->fram = fram;
if (loadValue)
this->loadValue();
}
void SmartVariable::loadValue()
{
this->fram->read(this->framAddress, (uint8_t *)this->value, this->size);
this->setValue(this->value);
}
void SmartVariable::saveValue()
{
this->fram->write(this->framAddress, (uint8_t *)this->value, this->size);
}
void SmartVariable::setValueAutoSave(bool autoSave)
{
this->autoSave = autoSave;
}
uint16_t SmartVariable::registerCallback(std::function<void(char *)> callback)
{
this->valueChangeCallbacks[this->currentHandlerId] = callback;
return this->currentHandlerId++;
}
void SmartVariable::unregisterCallback(uint16_t handlerId)
{
this->valueChangeCallbacks.erase(handlerId);
}
void SmartVariable::handleMqttCallback(char *topic, char *payload)
{
if (!strcmp(topic, this->valueRequestTopic))
{
this->publishValue();
}
else if (!strcmp(topic, this->setValueTopic))
{
this->setValue(payload);
}
}
void SmartVariable::subscribeMqtt()
{
if (this->iotEnabled)
{
ESP_LOGV("SmartVariable", "IoT Enabled, running MQTT Subscribe");
ESP_LOGV("SmartVariable", "Value Request: %d, Set Value: %d", this->useValueRequest, this->setValueEnabled);
if (this->useValueRequest) {
if (this->valueRequestTopic == nullptr) {
ESP_LOGE("SmartVariable", "Value Request Topic is NULL");
return;
}
ESP_LOGV("SmartVariable", "Subscribing to %s", this->valueRequestTopic);
this->iot->subscribe(this->valueRequestTopic);
}
if (this->setValueEnabled) {
if (this->setValueTopic == nullptr) {
ESP_LOGE("SmartVariable", "Set Value Topic is NULL");
return;
}
ESP_LOGV("SmartVariable", "Subscribing to %s", this->setValueTopic);
this->iot->subscribe(this->setValueTopic);
}
ESP_LOGV("SmartVariable", "Publishing Value");
this->publishValue();
}
}
int32_t SmartVariable::getIntValue()
{
return atoi(this->value);
}
void SmartVariable::setIntValue(int32_t value)
{
itoa(value, this->value, 10);
this->setValue(this->value);
}
double SmartVariable::getDoubleValue()
{
return atof(this->value);
}
void SmartVariable::setDoubleValue(double value)
{
dtostrf(value, 0, 2, this->value);
this->setValue(this->value);
}

View File

@ -0,0 +1,50 @@
#pragma once
#include <FRAM.h>
#include <ESPMegaIoT.hpp>
#include <map>
/**
* @brief SmartVariable is a local variable that can be accessed remotely and have FRAM support
*/
class SmartVariable {
public:
SmartVariable();
~SmartVariable();
void begin(size_t size);
void enableIoT(ESPMegaIoT* iot, const char* topic);
void enableValueRequest(const char* valueRequestTopic);
void setValue(const char* value);
char* getValue();
void enableSetValue(const char* setValueTopic);
void publishValue();
void bindFRAM(FRAM *fram, uint32_t framAddress);
void bindFRAM(FRAM *fram, uint32_t framAddress, bool loadValue);
void loadValue();
void saveValue();
void setValueAutoSave(bool autoSave);
uint16_t registerCallback(std::function<void(char*)> callback);
void unregisterCallback(uint16_t handlerId);
int32_t getIntValue();
void setIntValue(int32_t value);
double getDoubleValue();
void setDoubleValue(double value);
protected:
ESPMegaIoT* iot;
bool iotEnabled;
const char* topic;
char* value;
size_t size;
bool useValueRequest;
const char* valueRequestTopic;
bool setValueEnabled;
const char* setValueTopic;
bool autoSave;
FRAM *fram;
uint32_t framAddress;
void handleMqttCallback(char* topic, char* payload);
void subscribeMqtt();
// Value Change Callback
uint16_t currentHandlerId;
std::map<uint16_t, std::function<void(char*)>> valueChangeCallbacks;
};

View File

@ -32,4 +32,5 @@ lib_deps = adafruit/Adafruit PWM Servo Driver Library@^2.4.1
bblanchon/ArduinoJson@^6.21.4
monitor_speed = 115200
build_flags = -DCORE_DEBUG_LEVEL=5
extra_scripts = pre:helper_scripts/html2cpp.py
extra_scripts = pre:helper_scripts/html2cpp.py
monitor_port = COM36

View File

@ -1,3 +1,7 @@
/**
* @file main.cpp
* @brief Test firmware for the ESPMegaPRO OOP library
*/
#include <ESPMegaProOS.hpp>
#include <InternalDisplay.hpp>
#include <ETH.h>
@ -6,17 +10,19 @@
#include <RemoteVariable.hpp>
#include <CurrentTransformerCard.hpp>
#include <AnalogCard.hpp>
#include <SmartVariable.hpp>
// #define FRAM_DEBUG
// #define MQTT_DEBUG
// #define WRITE_DEFAULT_NETCONF
#define WRITE_DEFAULT_NETCONF
//#define CLIMATE_CARD_ENABLE
//#define MQTT_CARD_REGISTER
#define DISPLAY_ENABLE
#define MQTT_CARD_REGISTER
//#define DISPLAY_ENABLE
#define WEB_SERVER_ENABLE
#define LCD_OTA_ENABLE
#define REMOTE_VARIABLE_ENABLE
#define CT_ENABLE
//#define LCD_OTA_ENABLE
//#define REMOTE_VARIABLE_ENABLE
//#define CT_ENABLE
#define SMART_VARIABLE_ENABLE
// Demo PLC firmware using the ESPMegaPRO OOP library
@ -41,6 +47,10 @@ float voltage = 220.0;
CurrentTransformerCard ct = CurrentTransformerCard(&analogCard, 0, &voltage, adc2current, 1000);
#endif
#ifdef SMART_VARIABLE_ENABLE
SmartVariable smartVar = SmartVariable();
#endif
#ifdef CLIMATE_CARD_ENABLE
// Climate Card
const char *mode_names[] = {"off", "fan_only", "cool"};
@ -119,7 +129,7 @@ void mqtt_callback(char *topic, char *payload)
void setNetworkConfig()
{
NetworkConfig config = {
.ip = {192, 168, 0, 10},
.ip = {192, 168, 0, 249},
.gateway = {192, 168, 0, 1},
.subnet = {255, 255, 255, 0},
.dns1 = {10, 192, 1, 1},
@ -142,7 +152,7 @@ void setMqttConfig()
.mqtt_port = 1883,
.mqtt_useauth = false};
strcpy(config.mqtt_server, "192.168.0.26");
strcpy(config.base_topic, "/espmegaoop");
strcpy(config.base_topic, "/espmegacud");
espmega.iot->setMqttConfig(config);
espmega.iot->saveMqttConfig();
}
@ -226,6 +236,20 @@ void setup()
ct.bindFRAM(&espmega.fram, 7000);
ct.loadEnergy();
ct.setEnergyAutoSave(true);
#endif
#ifdef SMART_VARIABLE_ENABLE
ESP_LOGI("Initializer", "Initializing smart variable");
smartVar.begin(16);
ESP_LOGI("Initializer", "Binding smart variable to FRAM");
smartVar.bindFRAM(&espmega.fram, 8000);
ESP_LOGI("Initializer", "Enabling smart variable autosave");
smartVar.setValueAutoSave(true);
ESP_LOGI("Initializer", "Enabling IoT for smart variable");
smartVar.enableIoT(espmega.iot, "/smartvar");
ESP_LOGI("Initializer", "Enabling smart variable set value");
smartVar.enableSetValue("/smartvar/set");
ESP_LOGI("Initializer", "Enabling smart variable value request");
smartVar.enableValueRequest("/smartvar/request");
#endif
ESP_LOGI("Initializer", "Setup complete");
}
@ -283,4 +307,22 @@ void loop()
Serial.println(ct.getCurrent());
}
#endif
#ifdef SMART_VARIABLE_ENABLE
static uint32_t last_smartvar_print = 0;
if (millis() - last_smartvar_print >= 1000)
{
last_smartvar_print = millis();
Serial.print("SmartVar: ");
Serial.println(smartVar.getValue());
}
static bool last_smartvar_state = false;
static uint32_t last_smartvar_state_change = 0;
if (millis() - last_smartvar_state_change >= 5000)
{
last_smartvar_state_change = millis();
last_smartvar_state = !last_smartvar_state;
smartVar.setValue(last_smartvar_state ? "true" : "false");
}
#endif
}

18
IRLearner/.vscode/c_cpp_properties.json vendored Normal file
View File

@ -0,0 +1,18 @@
{
"configurations": [
{
"name": "windows-gcc-x64",
"includePath": [
"${workspaceFolder}/**"
],
"compilerPath": "gcc",
"cStandard": "${default}",
"cppStandard": "${default}",
"intelliSenseMode": "windows-gcc-x64",
"compilerArgs": [
""
]
}
],
"version": 4
}

24
IRLearner/.vscode/launch.json vendored Normal file
View File

@ -0,0 +1,24 @@
{
"version": "0.2.0",
"configurations": [
{
"name": "C/C++ Runner: Debug Session",
"type": "cppdbg",
"request": "launch",
"args": [],
"stopAtEntry": false,
"externalConsole": true,
"cwd": "d:/Git/ESPMegaPRO-v3-SDK/IRLearner",
"program": "d:/Git/ESPMegaPRO-v3-SDK/IRLearner/build/Debug/outDebug",
"MIMode": "gdb",
"miDebuggerPath": "gdb",
"setupCommands": [
{
"description": "Enable pretty-printing for gdb",
"text": "-enable-pretty-printing",
"ignoreFailures": true
}
]
}
]
}

59
IRLearner/.vscode/settings.json vendored Normal file
View File

@ -0,0 +1,59 @@
{
"C_Cpp_Runner.cCompilerPath": "gcc",
"C_Cpp_Runner.cppCompilerPath": "g++",
"C_Cpp_Runner.debuggerPath": "gdb",
"C_Cpp_Runner.cStandard": "",
"C_Cpp_Runner.cppStandard": "",
"C_Cpp_Runner.msvcBatchPath": "",
"C_Cpp_Runner.useMsvc": false,
"C_Cpp_Runner.warnings": [
"-Wall",
"-Wextra",
"-Wpedantic",
"-Wshadow",
"-Wformat=2",
"-Wcast-align",
"-Wconversion",
"-Wsign-conversion",
"-Wnull-dereference"
],
"C_Cpp_Runner.msvcWarnings": [
"/W4",
"/permissive-",
"/w14242",
"/w14287",
"/w14296",
"/w14311",
"/w14826",
"/w44062",
"/w44242",
"/w14905",
"/w14906",
"/w14263",
"/w44265",
"/w14928"
],
"C_Cpp_Runner.enableWarnings": true,
"C_Cpp_Runner.warningsAsError": false,
"C_Cpp_Runner.compilerArgs": [],
"C_Cpp_Runner.linkerArgs": [],
"C_Cpp_Runner.includePaths": [],
"C_Cpp_Runner.includeSearch": [
"*",
"**/*"
],
"C_Cpp_Runner.excludeSearch": [
"**/build",
"**/build/**",
"**/.*",
"**/.*/**",
"**/.vscode",
"**/.vscode/**"
],
"C_Cpp_Runner.useAddressSanitizer": false,
"C_Cpp_Runner.useUndefinedSanitizer": false,
"C_Cpp_Runner.useLeakSanitizer": false,
"C_Cpp_Runner.showCompilationTime": false,
"C_Cpp_Runner.useLinkTimeOptimization": false,
"C_Cpp_Runner.msvcSecureNoWarnings": false
}

0
IRLearner/main.hpp Normal file
View File