Skip to content

Commit

Permalink
correct accidental dirty commit
Browse files Browse the repository at this point in the history
  • Loading branch information
arjenhiemstra committed Mar 12, 2024
1 parent c596cbd commit 23b57b2
Show file tree
Hide file tree
Showing 3 changed files with 79 additions and 67 deletions.
17 changes: 9 additions & 8 deletions software/NRG_itho_wifi/main/IthoSystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ void getSetting(const uint8_t index, const bool updateState, const bool updatewe
return;
}

//const struct ihtoDeviceType *settingsPtr = ithoDeviceptr;
// const struct ihtoDeviceType *settingsPtr = ithoDeviceptr;

JsonDocument doc;
JsonObject root = doc.to<JsonObject>();
Expand Down Expand Up @@ -521,7 +521,7 @@ void sendRemoteCmd(const uint8_t remoteIndex, const IthoCommand command)
i2c_header[8] = (curtime >> 8) & 0xFF;
i2c_header[9] = curtime & 0xFF;

const uint8_t *id = virtualRemotes.getRemoteIDbyIndex(remoteIndex);
const int *id = virtualRemotes.getRemoteIDbyIndex(remoteIndex);
i2c_header[11] = *id;
i2c_header[12] = *(id + 1);
i2c_header[13] = *(id + 2);
Expand Down Expand Up @@ -1452,8 +1452,8 @@ void setSettingCE30(uint16_t temporary_temperature, uint16_t fallback_temperatur

void setSetting4030(uint16_t index, uint8_t datatype, uint16_t value, uint8_t checked, bool updateweb)
{
uint8_t command[] = {0x82,0x80,0x40,0x30,0x06,0x07,0x01,0x00,0x0F,0x00,0x01,0x01,0x01,0xFF};
uint8_t command[] = {0x82, 0x80, 0x40, 0x30, 0x06, 0x07, 0x01, 0x00, 0x0F, 0x00, 0x01, 0x01, 0x01, 0xFF};

command[7] = (index >> 8) & 0xFF;
command[8] = index & 0xFF;

Expand All @@ -1467,8 +1467,9 @@ void setSetting4030(uint16_t index, uint8_t datatype, uint16_t value, uint8_t ch
command[sizeof(command) - 1] = checksum(command, sizeof(command) - 1);

D_LOG("Sending 4030: %s", i2cbuf2string(command, sizeof(command)).c_str());
if (updateweb) jsonSysmessage("itho_4030_result", i2cbuf2string(command, sizeof(command)).c_str());

if (updateweb)
jsonSysmessage("itho_4030_result", i2cbuf2string(command, sizeof(command)).c_str());

if (!i2c_sendBytes(command, sizeof(command), I2C_CMD_SET_CE30))
{
if (updateweb)
Expand All @@ -1477,7 +1478,7 @@ void setSetting4030(uint16_t index, uint8_t datatype, uint16_t value, uint8_t ch
jsonSysmessage("itho_4030_result", "failed");
}
return;
}
}
}

int32_t *sendQuery2410(uint8_t index, bool updateweb)
Expand Down Expand Up @@ -1796,7 +1797,7 @@ void filterReset()
command[8] = (curtime >> 8) & 0xFF;
command[9] = curtime & 0xFF;

const uint8_t *id = virtualRemotes.getRemoteIDbyIndex(0);
const int *id = virtualRemotes.getRemoteIDbyIndex(0);
command[11] = *id;
command[12] = *(id + 1);
command[13] = *(id + 2);
Expand Down
125 changes: 68 additions & 57 deletions software/NRG_itho_wifi/main/tasks/task_cc1101.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,36 +10,50 @@ uint8_t debugLevel = 0;

// locals
StaticTask_t xTaskCC1101Buffer;
StackType_t xTaskCC1101Stack[STACK_SIZE_MEDIUM];
StackType_t xTaskCC1101Stack[STACK_SIZE];

IthoCommand RFTcommand[3] = {IthoUnknown, IthoUnknown, IthoUnknown};
byte RFTRSSI[3] = {0, 0, 0};
byte RFTcommandpos = 0;
bool RFTidChk[3] = {false, false, false};
// Ticker LogMessage;
Ticker timerLearnLeaveMode;

volatile bool ithoCheck = false;
SemaphoreHandle_t isrSemaphore;

IRAM_ATTR void ITHOinterrupt()
{
// Try to take the semaphore
if (xSemaphoreTakeFromISR(isrSemaphore, NULL) == pdTRUE)
{
// ISR code here

ithoCheck = rf.receivePacket();

// At the end, give back the semaphore
xSemaphoreGiveFromISR(isrSemaphore, NULL);
}
ithoCheck = true;
}

void disableRFsupport()
{
detachInterrupt(itho_irq_pin);
}

void RFDebug(IthoPacket *packetPtr, IthoCommand cmd)
uint8_t findRFTlastCommand()
{
if (RFTcommand[RFTcommandpos] != IthoUnknown)
return RFTcommandpos;
if ((RFTcommandpos == 0) && (RFTcommand[2] != IthoUnknown))
return 2;
if ((RFTcommandpos == 0) && (RFTcommand[1] != IthoUnknown))
return 1;
if ((RFTcommandpos == 1) && (RFTcommand[0] != IthoUnknown))
return 0;
if ((RFTcommandpos == 1) && (RFTcommand[2] != IthoUnknown))
return 2;
if ((RFTcommandpos == 2) && (RFTcommand[1] != IthoUnknown))
return 1;
if ((RFTcommandpos == 2) && (RFTcommand[0] != IthoUnknown))
return 0;
return -1;
}

void RFDebug(IthoCommand cmd)
{
char debugLog[400] = {0};
strncat(debugLog, rf.LastMessageDecoded(packetPtr).c_str(), sizeof(debugLog) - strlen(debugLog) - 1);
strncat(debugLog, rf.LastMessageDecoded().c_str(), sizeof(debugLog) - strlen(debugLog) - 1);
// log command
switch (cmd)
{
Expand Down Expand Up @@ -181,7 +195,7 @@ void startTaskCC1101()
xTaskCC1101Handle = xTaskCreateStaticPinnedToCore(
TaskCC1101,
"TaskCC1101",
STACK_SIZE_MEDIUM,
STACK_SIZE,
(void *)1,
TASK_CC1101_PRIO,
xTaskCC1101Stack,
Expand All @@ -200,14 +214,14 @@ void TaskCC1101(void *pvParameters)
{
Ticker reboot;

// switch off rf_support in case init fails
// switch off rf_support
systemConfig.itho_rf_support = 0;
systemConfig.rfInitOK = false;

// attach saveConfig and reboot script to fire after 2 sec
reboot.attach(2, []()
{
E_LOG("Setup: CC1101 RF module not found");
E_LOG("Setup: init of CC1101 RF module failed");
saveSystemConfig("flash");
delay(1000);
ACTIVE_FS.end();
Expand All @@ -216,21 +230,19 @@ void TaskCC1101(void *pvParameters)
// init the RF module
rf.init();
pinMode(itho_irq_pin, INPUT);
isrSemaphore = xSemaphoreCreateBinary();
attachInterrupt(itho_irq_pin, ITHOinterrupt, RISING);
xSemaphoreGive(isrSemaphore);

// this portion of code will not be reached when no RF module is present: detach reboot script, switch on rf_supprt and load remotes config
esp_task_wdt_add(NULL);
reboot.detach();
N_LOG("Setup: CC1101 RF module activated");
N_LOG("Setup: init of CC1101 RF module successful");
rf.setDeviceIDsend(sys.getMac(3), sys.getMac(4), sys.getMac(5) - 1);
systemConfig.itho_rf_support = 1;
loadRemotesConfig("flash");
// rf.setBindAllowed(true);
for (int i = 0; i < remotes.getRemoteCount(); i++)
{
const uint8_t *id = remotes.getRemoteIDbyIndex(i);
const int *id = remotes.getRemoteIDbyIndex(i);
rf.updateRFDeviceID(*id, *(id + 1), *(id + 2), i);
rf.updateRFDeviceType(remotes.getRemoteType(i), i);
rf.setRFDeviceBidirectional(i, remotes.getRemoteFunction(i) == RemoteFunctions::BIDIRECT ? true : false);
Expand All @@ -251,38 +263,41 @@ void TaskCC1101(void *pvParameters)
if (ithoCheck)
{
ithoCheck = false;

D_LOG("getpacketBufferCount: %d", rf.getpacketBufferCount());

while (rf.getpacketBufferCount() > 0)
if (rf.checkForNewPacket())
{
IthoPacket packet = rf.checkForNewPacket();
rf.parseMessage(&packet);

uint8_t *lastID = rf.getLastID(&packet);

IthoCommand cmd = rf.getLastCommand(&packet);
RemoteTypes remtype = rf.getLastRemType(&packet);
bool chk = remotes.checkID(*(lastID + 0), *(lastID + 1), *(lastID + 2));
D_LOG("id:%02X,%02X,%02X chk: %d", *(lastID + 0), *(lastID + 1), *(lastID + 2), chk);
int *lastID = rf.getLastID();
int id[3];
for (uint8_t i = 0; i < 3; i++)
{
id[i] = *(&lastID[0] + i);
}
IthoCommand cmd = rf.getLastCommand();
RemoteTypes remtype = rf.getLastRemType();
if (++RFTcommandpos > 2)
RFTcommandpos = 0; // store information in next entry of ringbuffers
RFTcommand[RFTcommandpos] = cmd;
RFTRSSI[RFTcommandpos] = rf.ReadRSSI();
// int *lastID = rf.getLastID();
bool chk = remotes.checkID(id);
// bool chk = rf.checkID(RFTid);
RFTidChk[RFTcommandpos] = chk;
if (debugLevel >= 2)
{
if (chk || debugLevel == 3)
{
RFDebug(&packet, cmd);
RFDebug(cmd);
}
}

if (cmd != IthoUnknown)
{ // only act on good cmd
if (debugLevel == 1)
{
RFDebug(&packet, cmd);
RFDebug(cmd);
}
if (cmd == IthoLeave && remotes.remoteLearnLeaveStatus())
{
D_LOG("Leave command received. Trying to remove remote...");
int result = remotes.removeRemote(*(lastID + 0), *(lastID + 1), *(lastID + 2));
int result = remotes.removeRemote(id);
switch (result)
{
case -1: // failed! - remote not registered
Expand All @@ -297,32 +312,28 @@ void TaskCC1101(void *pvParameters)
if (cmd == IthoJoin)
{
D_LOG("Join command received. Trying to join remote...");
D_LOG("ID:%02X,%02X,%02X", *(lastID + 0), *(lastID + 1), *(lastID + 2));
D_LOG("ID:%02X,%02X,%02X", id[0], id[1], id[2]);
if (remotes.remoteLearnLeaveStatus())
{
D_LOG("Join allowed...");

int result = remotes.registerNewRemote(*(lastID + 0), *(lastID + 1), *(lastID + 2), remtype);
int result = remotes.registerNewRemote(id, remtype);
if (result >= 0)
{
D_LOG("registerNewRemote success, index:%d", result);
if (remotes.getRemoteFunction(result) == RemoteFunctions::BIDIRECT)
{
delay(500);
rf.setSendTries(1);
rf.sendJoinReply(*(lastID + 0), *(lastID + 1), *(lastID + 2));
D_LOG("Join reply send");
delay(100);
rf.send10E0();
D_LOG("10E0 send");
rf.setSendTries(3);
// delay(500);
// rf.setSendTries(1);
// rf.sendJoinReply(id[0],id[1],id[2]);
// D_LOG("Join reply send");
// delay(100);
// rf.send10E0();
// D_LOG("10E0 send");
// rf.setSendTries(3);
}

saveRemotesflag = true;
}
else
{
D_LOG("registerNewRemote failed, code:%d", result);
// error
// case -1: // failed! - remote already registered
// break;
Expand All @@ -331,7 +342,7 @@ void TaskCC1101(void *pvParameters)
}
if (virtualRemotes.remoteLearnLeaveStatus())
{
int result = virtualRemotes.registerNewRemote(*(lastID + 0), *(lastID + 1), *(lastID + 2), remtype);
int result = virtualRemotes.registerNewRemote(id, remtype);
if (result >= 0)
{
saveVremotesflag = true;
Expand All @@ -350,8 +361,8 @@ void TaskCC1101(void *pvParameters)
}
if (chk)
{
remotes.lastRemoteName = remotes.getRemoteNamebyIndex(remotes.remoteIndex(*(lastID + 0), *(lastID + 1), *(lastID + 2)));
if (remotes.getRemoteFunction(remotes.remoteIndex(*(lastID + 0), *(lastID + 1), *(lastID + 2))) != RemoteFunctions::MONITOR)
remotes.lastRemoteName = remotes.getRemoteNamebyIndex(remotes.remoteIndex(id));
if (remotes.getRemoteFunction(remotes.remoteIndex(id)) != RemoteFunctions::MONITOR)
{
if (cmd == IthoLow)
{
Expand Down Expand Up @@ -415,9 +426,9 @@ void TaskCC1101(void *pvParameters)
const ithoRFDevices &rfDevices = rf.getRFdevices();
for (auto &item : rfDevices.device)
{
if (item.deviceId[0] == 0 && item.deviceId[1] == 0 && item.deviceId[2] == 0)
if (item.deviceId == 0)
continue;
int remIndex = remotes.remoteIndex(item.deviceId[0], item.deviceId[1], item.deviceId[2]);
int remIndex = remotes.remoteIndex(item.deviceId);
if (remIndex != -1)
{
remotes.addCapabilities(remIndex, "timestamp", item.timestamp);
Expand Down
4 changes: 2 additions & 2 deletions software/NRG_itho_wifi/main/tasks/task_cc1101.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@

#include "LittleFS.h"


// globals
extern Ticker TaskCC1101Timeout;
extern TaskHandle_t xTaskCC1101Handle;
Expand All @@ -31,7 +30,8 @@ extern uint8_t debugLevel;

IRAM_ATTR void ITHOinterrupt();
void disableRFsupport();
void RFDebug(IthoPacket *packetPtr, IthoCommand cmd);
uint8_t findRFTlastCommand();
void RFDebug(IthoCommand cmd);
void toggleRemoteLLmode(const char *remotetype);
void setllModeTimer();
void startTaskCC1101();
Expand Down

0 comments on commit 23b57b2

Please sign in to comment.