Skip to content

Commit

Permalink
fix for clashing key press counter send by different channels
Browse files Browse the repository at this point in the history
  • Loading branch information
loetmeister committed Nov 1, 2021
1 parent 9fc40ca commit c6bcf76
Show file tree
Hide file tree
Showing 20 changed files with 1,637 additions and 1,629 deletions.
2 changes: 1 addition & 1 deletion HBW-LC-BL-4/HBW-LC-Bl-4.ino
Expand Up @@ -33,7 +33,7 @@


#define HARDWARE_VERSION 0x01
#define FIRMWARE_VERSION 0x0033
#define FIRMWARE_VERSION 0x0034
#define HMW_DEVICETYPE 0x82 //BL4 device (make sure to import hbw_lc_bl-4.xml into FHEM)

#define NUMBER_OF_BLINDS 4
Expand Down
1,565 changes: 773 additions & 792 deletions HBW-LC-BL-4/HBW-LC-Bl-4.ino.eightanaloginputs.hex

Large diffs are not rendered by default.

1,564 changes: 772 additions & 792 deletions HBW-LC-BL-4/HBW-LC-Bl-4.ino.with_bootloader.eightanaloginputs.hex

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion HBW-LC-BL-8/HBW-LC-Bl-8.ino
Expand Up @@ -29,7 +29,7 @@


#define HARDWARE_VERSION 0x01
#define FIRMWARE_VERSION 0x0022
#define FIRMWARE_VERSION 0x0023
#define HMW_DEVICETYPE 0x92 //BL8 device (make sure to import hbw_lc_bl-8.xml into FHEM)

#define NUMBER_OF_BLINDS 8
Expand Down
2 changes: 1 addition & 1 deletion HBW-LC-Sw-12/HBW-LC-Sw-12.ino
Expand Up @@ -27,7 +27,7 @@


#define HARDWARE_VERSION 0x01
#define FIRMWARE_VERSION 0x002B
#define FIRMWARE_VERSION 0x002D
#define HMW_DEVICETYPE 0x93

//#define USE_HARDWARE_SERIAL // use hardware serial (USART) for final device - this disables debug output
Expand Down
21 changes: 13 additions & 8 deletions HBW-LC-Sw-12/HBWSwitchSerialAdvanced.cpp
Expand Up @@ -3,7 +3,7 @@
*
* see "HBWSwitchSerialAdvanced.h" for details
*
* Updated: 02.07.2021
* Updated: 01.11.2021
*
* http://loetmeister.de/Elektronik/homematic/index.htm#modules
*
Expand All @@ -19,18 +19,19 @@ HBWSwitchSerialAdvanced::HBWSwitchSerialAdvanced(uint8_t _relayPos, uint8_t _led
config = _config;
shiftRegister = _shiftRegister;
relayOperationPending = false;
relayLevel = OFF;

StateMachine.init();
clearFeedback();
// StateMachine.setCurrentState(UNKNOWN_STATE); - not needed, as using LED shiftRegister state for init and re-reads
// StateMachine.setCurrentState(UNKNOWN_STATE); - not needed, as using seperate state for init and re-reads
};


// channel specific settings or defaults
// (This function is called after device read config from EEPROM)
void HBWSwitchSerialAdvanced::afterReadConfig() {

uint8_t level = shiftRegister->get(ledPos); // read current state (is zero/LOW on device reset), but keeps state on EEPROM re-read!
uint8_t level = relayLevel; // relay state is OFF on device reset, but maintain state on EEPROM re-read!

//perform intial reset (or set if inverterted) for all relays - bistable relays may have random state!
if (level) { // set to 0 or 1
Expand All @@ -49,9 +50,11 @@ void HBWSwitchSerialAdvanced::afterReadConfig() {

void HBWSwitchSerialAdvanced::set(HBWDevice* device, uint8_t length, uint8_t const * const data) {

if (length >= 8) { // got called with additional peering parameters -- test for correct NUM_PEER_PARAMS
if (length >= 9) { // got called with additional peering parameters -- test for correct NUM_PEER_PARAMS

StateMachine.writePeerParamActionType(*(data));
uint8_t currentKeyNum = data[7];
bool sameLastSender = data[8];

#ifdef DEBUG_OUTPUT
hbwdebug(F("cKeyNum: "));
Expand All @@ -60,7 +63,7 @@ void HBWSwitchSerialAdvanced::set(HBWDevice* device, uint8_t length, uint8_t con
#endif

if (StateMachine.peerParam_getActionType() >1) { // ACTION_TYPE
if (!StateMachine.stateTimerRunning && StateMachine.lastKeyNum != currentKeyNum) { // do not interrupt running timer, ignore LONG_MULTIEXECUTE
if (!StateMachine.stateTimerRunning && (StateMachine.lastKeyNum != currentKeyNum || (StateMachine.lastKeyNum == currentKeyNum && !sameLastSender))) { // do not interrupt running timer, no repeated long press here (LONG_MULTIEXECUTE ingnored)
byte level;
if (StateMachine.peerParam_getActionType() == 2) // TOGGLE_TO_COUNTER
level = ((currentKeyNum %2 == 0) ? 0 : 200); // (switch ON at odd numbers, OFF at even numbers)
Expand All @@ -79,7 +82,7 @@ void HBWSwitchSerialAdvanced::set(HBWDevice* device, uint8_t length, uint8_t con
#endif
}
}
else if (StateMachine.lastKeyNum == currentKeyNum && !StateMachine.peerParam_getLongMultiexecute()) {
else if ((StateMachine.lastKeyNum == currentKeyNum && sameLastSender) && !StateMachine.peerParam_getLongMultiexecute()) {
// repeated key event for ACTION_TYPE == 1 (ACTION_TYPE == 0 already filtered by receiveKeyEvent, HBWLinkReceiver)
// repeated long press, but LONG_MULTIEXECUTE not enabled
}
Expand Down Expand Up @@ -118,7 +121,7 @@ void HBWSwitchSerialAdvanced::set(HBWDevice* device, uint8_t length, uint8_t con
/* standard public function - returns length of data array. Data array contains current channel reading */
uint8_t HBWSwitchSerialAdvanced::get(uint8_t* data)
{
(*data++) = (shiftRegister->get(ledPos)) ? 200 : 0;
(*data++) = relayLevel == ON ? 200 : 0;
*data = StateMachine.stateTimerRunning ? 64 : 0; // state flag 'working'

return 2;
Expand All @@ -132,7 +135,7 @@ void HBWSwitchSerialAdvanced::setOutput(HBWDevice* device, uint8_t const * const
uint8_t level = *(data);

if (level > 200) // toggle
level = !shiftRegister->get(ledPos); // get current state and negate
level = !relayLevel; // get current state and negate
else if (level) { // set to 0 or 1
level = (LOW ^ config->n_inverted);
shiftRegister->set(ledPos, HIGH); // set LEDs (register used for actual state!)
Expand All @@ -157,10 +160,12 @@ void HBWSwitchSerialAdvanced::operateRelay(uint8_t _newLevel)
if (_newLevel) { // on - perform set
shiftRegister->set(relayPos +1, LOW); // reset coil (remove power first - for safety)
shiftRegister->set(relayPos, HIGH); // power set coil
relayLevel = ON;
}
else { // off - perform reset
shiftRegister->set(relayPos, LOW); // set coil (remove power first - for safety)
shiftRegister->set(relayPos +1, HIGH); // power reset coil
relayLevel = OFF;
}

relayOperationTimeStart = millis(); // relay coil power must be removed after some ms (bistable relays!!)
Expand Down
7 changes: 5 additions & 2 deletions HBW-LC-Sw-12/HBWSwitchSerialAdvanced.h
Expand Up @@ -8,7 +8,7 @@
* Peering mit TOGGLE, TOGGLE_TO_COUNTER, TOGGLE_INVERSE_TO_COUNTER, onTime,
* offTime (Ein-/Ausschaltdauer), onDelayTime, offDelayTime (Ein-/Ausschaltverzögerung).
*
* Updated: 10.04.2021
* Updated: 01.11.2021
*
* TODO: join redundant code with HBWSwitchAdvanced into one lib
*
Expand All @@ -27,8 +27,10 @@

#define SHIFT_REGISTER_CLASS ShiftRegister74HC595<3> // Daisy chain 3 registers

#define RELAY_PULSE_DUARTION 80 // HIG duration in ms, to set or reset double coil latching relay safely
#define RELAY_PULSE_DUARTION 80 // HIGH duration in ms, to set or reset double coil latching relay safely

#define OFF false
#define ON true


class HBWSwitchSerialAdvanced : public HBWChannel {
Expand All @@ -54,6 +56,7 @@ class HBWSwitchSerialAdvanced : public HBWChannel {
protected:
void setOutput(HBWDevice*, uint8_t const * const data);
bool relayOperationPending;
bool relayLevel; // current logical level
void operateRelay(uint8_t _newLevel);
uint32_t relayOperationTimeStart;
};
Expand Down
2 changes: 1 addition & 1 deletion HBW-SC-10-Dim-6/HBW-SC-10-Dim-6.ino
Expand Up @@ -35,7 +35,7 @@


#define HARDWARE_VERSION 0x01
#define FIRMWARE_VERSION 0x003D
#define FIRMWARE_VERSION 0x003E
#define HMW_DEVICETYPE 0x96 //device ID (make sure to import hbw_io-10_dim-6.xml into FHEM)

#define NUMBER_OF_INPUT_CHAN 10 // input channel - pushbutton, key, other digital in
Expand Down
6 changes: 3 additions & 3 deletions HBW-SC-10-Dim-6/HBWDimmerVirtual.cpp
Expand Up @@ -21,11 +21,11 @@ void HBWDimmerVirtual::set(HBWDevice* device, uint8_t length, uint8_t const * co
if (length == 1 && *(data) <= 200) { // level set by FHEM/CCU
level = *(data);
}
else if (length == NUM_PEER_PARAMS +1)
else if (length == NUM_PEER_PARAMS +2)
{
// create new (writable) array
uint8_t dataNew[NUM_PEER_PARAMS +1];
memcpy(dataNew, data, NUM_PEER_PARAMS +1);
uint8_t dataNew[NUM_PEER_PARAMS +2];
memcpy(dataNew, data, NUM_PEER_PARAMS +2);

//handleLogic(config->logic, data, dataNew);
dataNew[D_POS_onLevel] = handleLogic(dataNew[D_POS_onLevel], level);
Expand Down
11 changes: 7 additions & 4 deletions libraries/src/HBWBlind.cpp
Expand Up @@ -6,7 +6,7 @@
** Infos: http://loetmeister.de/Elektronik/homematic/index.htm#modules
** Vorlage: https://github.com/loetmeister/HM485-Lib/tree/markus/HBW-LC-Bl4
**
** Last updated: 08.02.2019
** Last updated: 01.11.2021
*/

#include "HBWBlind.h"
Expand Down Expand Up @@ -43,12 +43,15 @@ void HBWChanBl::afterReadConfig() {

void HBWChanBl::set(HBWDevice* device, uint8_t length, uint8_t const * const data) {

if (length == 2)
if (length == 3)
{
if (lastKeyNum == data[1]) // ignore repeated key press
uint8_t currentKeyNum = data[1];
bool sameLastSender = data[2];

if (lastKeyNum == currentKeyNum && sameLastSender) // ignore repeated key press from the same sender
return;
else
lastKeyNum = data[1];
lastKeyNum = currentKeyNum;
}

// blind control
Expand Down
16 changes: 9 additions & 7 deletions libraries/src/HBWDimmerAdvanced.cpp
Expand Up @@ -9,7 +9,7 @@
*
* http://loetmeister.de/Elektronik/homematic/
*
* Last updated: 16.04.2021
* Last updated: 01.11.2021
*/

#include "HBWDimmerAdvanced.h"
Expand Down Expand Up @@ -50,20 +50,22 @@ void HBWDimmerAdvanced::afterReadConfig()
/* standard public function - set a channel, directly or via peering event. Data array contains new value or all peering details */
void HBWDimmerAdvanced::set(HBWDevice* device, uint8_t length, uint8_t const * const data)
{
if (length >= NUM_PEER_PARAMS) // got called with additional peering parameters -- test for correct NUM_PEER_PARAMS
if (length >= NUM_PEER_PARAMS +2) // got called with additional peering parameters -- test for correct NUM_PEER_PARAMS
{
StateMachine.writePeerParamActionType(*(data));
StateMachine.writePeerConfigParam(data[D_POS_peerConfigParam]);
uint8_t currentKeyNum = data[NUM_PEER_PARAMS];
bool sameLastSender = data[NUM_PEER_PARAMS +1];

if (StateMachine.peerParam_getActionType() > JUMP_TO_TARGET) // all ACTION_TYPEs except JUMP_TO_TARGET will be covered here
{
if (StateMachine.currentStateIs(JT_ON) && (currentOnLevelPrio == ON_LEVEL_PRIO_HIGH && StateMachine.peerParam_onLevelPrioIsLow())) {
//do nothing in this case
// new low onLevelPrio should not overwrite high onLevelPrio when in "on" state
// do nothing in this case
}
else {
// do not interrupt running timer. First key press goes here, repeated press only when LONG_MULTIEXECUTE is enabled
if ((!StateMachine.stateTimerRunning) && ((StateMachine.lastKeyNum != currentKeyNum) || (StateMachine.lastKeyNum == currentKeyNum && StateMachine.peerParam_getLongMultiexecute()))) {
if ((!StateMachine.stateTimerRunning) && ((StateMachine.lastKeyNum != currentKeyNum || (StateMachine.lastKeyNum == currentKeyNum && !sameLastSender)) || (StateMachine.lastKeyNum == currentKeyNum && sameLastSender && StateMachine.peerParam_getLongMultiexecute()))) {

byte level = currentValue;

Expand Down Expand Up @@ -112,7 +114,7 @@ void HBWDimmerAdvanced::set(HBWDevice* device, uint8_t length, uint8_t const * c
}
}
}
else if (StateMachine.lastKeyNum == currentKeyNum && !StateMachine.peerParam_getLongMultiexecute()) {
else if (StateMachine.lastKeyNum == currentKeyNum && sameLastSender && !StateMachine.peerParam_getLongMultiexecute()) {
// repeated key event for ACTION_TYPE == 1 (ACTION_TYPE == 0 already filtered by receiveKeyEvent, HBWLinkReceiver)
// repeated long press, but LONG_MULTIEXECUTE not enabled
}
Expand All @@ -132,7 +134,7 @@ void HBWDimmerAdvanced::set(HBWDevice* device, uint8_t length, uint8_t const * c
)) {
// ON/OFF_TIME_ABSOLUTE running and in ON/OFF state, but new on/off time received is TIME_MINIMAL
// do nothing in this case
// or ON_TIME_ABSOLUTE with HIGH onLevelPrio cannot be overwritten with ON_TIME_ABSOLUTE LOW onLevelPrio - TODO: correct behaviour?
// or ON_TIME_ABSOLUTE with HIGH onLevelPrio cannot be overwritten with ON_TIME_ABSOLUTE & LOW onLevelPrio - TODO: correct behaviour?
}
else // action type: JUMP_TO_TARGET
{
Expand All @@ -154,7 +156,7 @@ void HBWDimmerAdvanced::set(HBWDevice* device, uint8_t length, uint8_t const * c
writePeerConfigStep(data[D_POS_peerConfigStep]);
writePeerConfigOffDtime(data[D_POS_peerConfigOffDtime]);

if (StateMachine.onLevel > 0 && StateMachine.onLevel >= StateMachine.onMinLevel) { // don't allow on_level 0 or below on_min_level
if (StateMachine.onLevel > 0 && StateMachine.onLevel >= StateMachine.onMinLevel) { // don't allow on_level 0 or below on_min_level // TODO: should this sanity check happen only when entering on or ramp_on state? right now it blocks all processing
StateMachine.forceStateChange(); // force update
}
}
Expand Down
3 changes: 2 additions & 1 deletion libraries/src/HBWDimmerAdvanced.h
Expand Up @@ -53,7 +53,8 @@
#define D_POS_dimMaxLevel 15
#define D_POS_peerConfigStep 16
#define D_POS_peerConfigOffDtime 17
#define D_POS_peerKeyPressNum 18 // last array element always used for keyPressNum
#define D_POS_peerKeyPressNum 18
#define D_POS_peerSameLastSender 19

#define BITMASK_DimStep B00001111
#define BITMASK_OffDelayStep B11110000
Expand Down
3 changes: 3 additions & 0 deletions libraries/src/HBWLinkBlindSimple.h
Expand Up @@ -20,6 +20,9 @@ class HBWLinkBlindSimple : public HBWLinkReceiver {
void receiveKeyEvent(HBWDevice* device, uint32_t senderAddress, uint8_t senderChannel,
uint8_t targetChannel, uint8_t keyPressNum, boolean longPress);
private:
uint32_t lastSenderAddress;
uint8_t lastSenderChannel;

static const uint8_t EEPROM_SIZE = 9; // "address_step" in XML
static const uint8_t NUM_PEER_PARAMS = 1; // number of bytes for long and short peering action each (without address and channel)
};
Expand Down
12 changes: 10 additions & 2 deletions libraries/src/HBWLinkBlindSimple.hpp
Expand Up @@ -25,8 +25,16 @@ void HBWLinkBlindSimple<numLinks, eepromStart>::receiveKeyEvent(HBWDevice* devic
uint32_t sndAddrEEPROM;
uint8_t channelEEPROM;
uint8_t actionType;
uint8_t data[NUM_PEER_PARAMS +1]; // store all peer parameter (use extra element for keyPressNum)
uint8_t data[NUM_PEER_PARAMS +2]; // store all peer parameter (use extra element for keyPressNum & sameLastSender)

data[NUM_PEER_PARAMS] = keyPressNum;
data[NUM_PEER_PARAMS +1] = false;

if (senderAddress == lastSenderAddress && senderChannel == lastSenderChannel) {
data[NUM_PEER_PARAMS +1] = true; // true, as this was the same sender (source device & channel) - sameLastSender
}
lastSenderAddress = senderAddress;
lastSenderChannel = senderChannel;

// read what to do from EEPROM
for(byte i = 0; i < numLinks; i++) {
Expand Down Expand Up @@ -73,6 +81,6 @@ void HBWLinkBlindSimple<numLinks, eepromStart>::receiveKeyEvent(HBWDevice* devic
// 5 -> INACTIVE
case 5: continue;
};
device->set(targetChannel, 2, data); // channel, data length, data
device->set(targetChannel, sizeof(data), data); // channel, data length, data
}
}
3 changes: 3 additions & 0 deletions libraries/src/HBWLinkDimmerAdvanced.h
Expand Up @@ -22,6 +22,9 @@ class HBWLinkDimmerAdvanced : public HBWLinkReceiver {
uint8_t targetChannel, uint8_t keyPressNum, boolean longPress);

private:
uint32_t lastSenderAddress;
uint8_t lastSenderChannel;

static const uint8_t EEPROM_SIZE = 42; // "address_step" in XML
static const uint8_t NUM_PEER_PARAMS = 18; // number of bytes for long and short peering action each (without address and channel)
};
Expand Down
15 changes: 11 additions & 4 deletions libraries/src/HBWLinkDimmerAdvanced.hpp
Expand Up @@ -24,10 +24,17 @@ void HBWLinkDimmerAdvanced<numLinks, eepromStart>::receiveKeyEvent(HBWDevice* de
uint32_t sndAddrEEPROM;
uint8_t channelEEPROM;
uint8_t actionType;

uint8_t data[NUM_PEER_PARAMS +1]; // store all peer parameter (use extra element for keyPressNum)
uint8_t data[NUM_PEER_PARAMS +2]; // store all peer parameter (use extra element for keyPressNum & sameLastSender)

data[NUM_PEER_PARAMS] = keyPressNum;
data[NUM_PEER_PARAMS +1] = false;

if (senderAddress == lastSenderAddress && senderChannel == lastSenderChannel) {
data[NUM_PEER_PARAMS +1] = true; // true, as this was the same sender (source device & channel) - sameLastSender
}
lastSenderAddress = senderAddress;
lastSenderChannel = senderChannel;

// read what to do from EEPROM
for(byte i = 0; i < numLinks; i++) {
device->readEEPROM(&sndAddrEEPROM, eepromStart + EEPROM_SIZE * i, 4, true);
Expand Down Expand Up @@ -63,7 +70,7 @@ void HBWLinkDimmerAdvanced<numLinks, eepromStart>::receiveKeyEvent(HBWDevice* de
// + 21 // SHORT_DIM_MAX_LEVEL
// + 22 // SHORT_DIM_STEP, SHORT_OFFDELAY_STEP
// + 23 // SHORT_OFFDELAY_NEWTIME, SHORT_OFFDELAY_OLDTIME
device->set(targetChannel, NUM_PEER_PARAMS +1, data); // channel, data length, data
device->set(targetChannel, sizeof(data), data); // channel, data length, data
}
}
// read specific long action eeprom section
Expand All @@ -75,7 +82,7 @@ void HBWLinkDimmerAdvanced<numLinks, eepromStart>::receiveKeyEvent(HBWDevice* de
// + 6+ NUM_PEER_PARAMS // LONG_ACTION_TYPE
// + 7+ NUM_PEER_PARAMS // LONG_ONDELAY_TIME
// ... and so on. Layout for LONG_* and SHORT_* must be the same
device->set(targetChannel, NUM_PEER_PARAMS +1, data); // channel, data length, data
device->set(targetChannel, sizeof(data), data); // channel, data length, data
}
}
}
Expand Down
3 changes: 3 additions & 0 deletions libraries/src/HBWLinkSwitchAdvanced.h
Expand Up @@ -22,6 +22,9 @@ class HBWLinkSwitchAdvanced : public HBWLinkReceiver {
uint8_t targetChannel, uint8_t keyPressNum, boolean longPress);

private:
uint32_t lastSenderAddress;
uint8_t lastSenderChannel;

static const uint8_t EEPROM_SIZE = 20; // "address_step" in XML
static const uint8_t NUM_PEER_PARAMS = 7; // number of bytes for long and short peering action each (without address and channel)
};
Expand Down

0 comments on commit c6bcf76

Please sign in to comment.