Skip to content

Commit

Permalink
new afterReadConfig mechanism, for device and channel
Browse files Browse the repository at this point in the history
  • Loading branch information
loetmeister committed Mar 8, 2018
1 parent 0b0e1a9 commit 2fe9cba
Show file tree
Hide file tree
Showing 7 changed files with 63 additions and 49 deletions.
12 changes: 6 additions & 6 deletions HBW-LC-BL-4/HBW-LC-Bl-4.ino
Expand Up @@ -94,12 +94,12 @@ class HBBlDevice : public HBWDevice {
// defaults setzen
if(hbwconfig.logging_time == 0xFF) hbwconfig.logging_time = 20;
// if(config.central_address == 0xFFFFFFFF) config.central_address = 0x00000001;
for(uint8_t channel = 0; channel < NUMBER_OF_BLINDS; channel++) {

if (hbwconfig.blindscfg[channel].blindTimeTopBottom == 0xFFFF) hbwconfig.blindscfg[channel].blindTimeTopBottom = 200;
if (hbwconfig.blindscfg[channel].blindTimeBottomTop == 0xFFFF) hbwconfig.blindscfg[channel].blindTimeBottomTop = 200;
if (hbwconfig.blindscfg[channel].blindTimeChangeOver == 0xFF) hbwconfig.blindscfg[channel].blindTimeChangeOver = 20;
};
// for(uint8_t channel = 0; channel < NUMBER_OF_BLINDS; channel++) {
//
// if (hbwconfig.blindscfg[channel].blindTimeTopBottom == 0xFFFF) hbwconfig.blindscfg[channel].blindTimeTopBottom = 200;
// if (hbwconfig.blindscfg[channel].blindTimeBottomTop == 0xFFFF) hbwconfig.blindscfg[channel].blindTimeBottomTop = 200;
// if (hbwconfig.blindscfg[channel].blindTimeChangeOver == 0xFF) hbwconfig.blindscfg[channel].blindTimeChangeOver = 20;
// };
};
};

Expand Down
4 changes: 2 additions & 2 deletions HBW-LC-Sw-12/HBW-LC-Sw-12.ino
Expand Up @@ -43,8 +43,8 @@
#define shiftRegOne_Clock 3 //SH_CP shift register clock input
#define shiftRegOne_Latch 4 //ST_CP storage register clock input
// extension shifregister for another 6 relays and LEDs
#define shiftRegTwo_Data 8
#define shiftRegTwo_Clock 7
#define shiftRegTwo_Data 12
#define shiftRegTwo_Clock 8
#define shiftRegTwo_Latch 9
#else
#define RS485_RXD 4
Expand Down
61 changes: 31 additions & 30 deletions HBW-LC-Sw-8/HBW-LC-Sw-8.ino
Expand Up @@ -12,7 +12,7 @@
// - Switch code in "HBWSwitch.h" channel library übertragen. neu: initConfigPins()
// v1.02
// - channel invert angepasst um nach einem Device reset (EEPROM 'gelöscht') keine Invertierung zu haben
// - fix: initConfigPins() muss nach Anlegen des HBSwDevice aufgerufen werden
// - fix: initConfigPins() in afterReadConfig() geändert.


#define HMW_DEVICETYPE 0x83
Expand Down Expand Up @@ -66,30 +66,31 @@ struct hbw_config {
HBWSwitch* switches[NUM_CHANNELS];


class HBSwDevice : public HBWDevice {
public:
HBSwDevice(uint8_t _devicetype, uint8_t _hardware_version, uint16_t _firmware_version,
Stream* _rs485, uint8_t _txen,
uint8_t _configSize, void* _config,
uint8_t _numChannels, HBWChannel** _channels,
Stream* _debugstream, HBWLinkSender* linksender = NULL, HBWLinkReceiver* linkreceiver = NULL) :
HBWDevice(_devicetype, _hardware_version, _firmware_version,
_rs485, _txen, _configSize, _config, _numChannels, ((HBWChannel**)(_channels)),
_debugstream, linksender, linkreceiver) {
// looks like virtual methods are not properly called here
afterReadConfig();
};

void afterReadConfig() {
// defaults setzen
if(hbwconfig.logging_time == 0xFF) hbwconfig.logging_time = 20;
// if(config.central_address == 0xFFFFFFFF) config.central_address = 0x00000001;
};
};


HBSwDevice* device = NULL;

//class HBSwDevice : public HBWDevice {
// public:
// HBSwDevice(uint8_t _devicetype, uint8_t _hardware_version, uint16_t _firmware_version,
// Stream* _rs485, uint8_t _txen,
// uint8_t _configSize, void* _config,
// uint8_t _numChannels, HBWChannel** _channels,
// Stream* _debugstream, HBWLinkSender* linksender = NULL, HBWLinkReceiver* linkreceiver = NULL) :
// HBWDevice(_devicetype, _hardware_version, _firmware_version,
// _rs485, _txen, _configSize, _config, _numChannels, ((HBWChannel**)(_channels)),
// _debugstream, linksender, linkreceiver) {
// // looks like virtual methods are not properly called here
// //afterReadConfig(); // TODO TEST - below defaults?
// };
//
// void afterReadConfig() {
// // defaults setzen
// if(hbwconfig.logging_time == 0xFF) hbwconfig.logging_time = 20;
// };
//};

//void HBWDevice::afterReadConfig() {
// if(hbwconfig.logging_time == 0xFF) hbwconfig.logging_time = 20;
//};
HBWDevice* device = NULL;
//HBSwDevice* device = NULL;

void setup()
{
Expand All @@ -104,17 +105,17 @@ void setup()
switches[i] = new HBWSwitch(pins[i], &(hbwconfig.switchcfg[i]));
};

device = new HBSwDevice(HMW_DEVICETYPE, HARDWARE_VERSION, FIRMWARE_VERSION,
device = new HBWDevice(HMW_DEVICETYPE, HARDWARE_VERSION, FIRMWARE_VERSION,
&rs485,RS485_TXEN,sizeof(hbwconfig),&hbwconfig,
NUM_CHANNELS,(HBWChannel**)switches,
&Serial,
NULL, new HBWLinkSwitchSimple(NUM_LINKS,LINKADDRESSSTART));

device->setConfigPins(); // 8 and 13 is the default
device->setConfigPins(BUTTON, LED); // 8 and 13 is the default

for(uint8_t i = 0; i < NUM_CHANNELS; i++){
switches[i]->initConfigPins(); // init output pins. Has to be called after the HBSwDevice object creation
};
// for(uint8_t i = 0; i < NUM_CHANNELS; i++){
// switches[i]->initConfigPins(); // init output pins. Has to be called after the HBSwDevice object creation
// };

hbwdebug(F("B: 2A "));
hbwdebug(freeRam());
Expand Down
5 changes: 2 additions & 3 deletions libraries/HBWSwitch/HBWSwitch.cpp
Expand Up @@ -12,12 +12,11 @@ HBWSwitch::HBWSwitch(uint8_t _pin, hbw_config_switch* _config) {
// TODO: das sollte einstellbar sein
// digitalWrite(pin, HIGH);
// pinMode(pin,OUTPUT);
// --> moved to initConfigPins()
// --> moved to afterReadConfig()
};


// init output pins. Has to be called after the HBSwDevice object creation in void setup()
void HBWSwitch::initConfigPins() {
void HBWSwitch::afterReadConfig() {
digitalWrite(pin, config->n_inverted ? LOW : HIGH); // 0=inverted, 1=not inverted (device reset will set to 1!)
pinMode(pin,OUTPUT);
}
Expand Down
3 changes: 2 additions & 1 deletion libraries/HBWSwitch/HBWSwitch.h
Expand Up @@ -24,7 +24,8 @@ class HBWSwitch : public HBWChannel {
virtual uint8_t get(uint8_t* data);
virtual void loop(HBWDevice*, uint8_t channel);
virtual void set(HBWDevice*, uint8_t length, uint8_t const * const data);
void initConfigPins();
//void initConfigPins();
virtual void afterReadConfig();
private:
uint8_t pin;
hbw_config_switch* config; // logging
Expand Down
22 changes: 17 additions & 5 deletions libraries/HBWired/HBWired.cpp
Expand Up @@ -426,7 +426,7 @@ void HBWDevice::processEvent(byte const * const frameData, byte frameDataLength,
break;
case 'K': // 0x4B Key-Event
case 0xCB: // 'Ë': // Key-Sim-Event TODO: Es gibt da einen theoretischen Unterschied
receiveKeyEvent(senderAddress, frameData[1], frameData[2], frameData[3] & 0x01);
receiveKeyEvent(senderAddress, frameData[1], frameData[2], frameData[3] & 0x01);
break;
case 'R': // Read EEPROM
// TODO: Check requested length...
Expand Down Expand Up @@ -677,7 +677,8 @@ void HBWDevice::readConfig() { // read config from EEPROM
config[i+1] = ((uint8_t*)(&addr))[3-i];
// set defaults if values not provided from EEPROM
// or other device specific stuff
afterReadConfig();
//afterReadConfig();
afterReadConfigPending = true; // tell main loop to run afterReadConfig() for device and channels //TODO test afterReadConfig
}


Expand Down Expand Up @@ -757,7 +758,8 @@ HBWDevice::HBWDevice(uint8_t _devicetype, uint8_t _hardware_version, uint16_t _f
ledPin = 0xFF; // inactive by default
useAnalogConfigPin = false; // use digital ConfigPin by default
// read config
readConfig();
readConfig();
afterReadConfigPending = true; // force read config after startup //TODO test afterReadConfig
}


Expand Down Expand Up @@ -801,6 +803,15 @@ uint8_t HBWDevice::get(uint8_t channel, uint8_t* data) { // returns length
// The loop function is called in an endless loop
void HBWDevice::loop()
{
// read device and channel config, on init and if triggered by ReadConfig() // TODO test afterReadConfig
if (afterReadConfigPending) {
afterReadConfig();
for(uint8_t i = 0; i < numChannels; i++) {
if (afterReadConfigPending)
channels[i]->afterReadConfig(); // TODO test afterReadConfig
}
afterReadConfigPending = false;
}
// Daten empfangen und alles, was zur Kommunikationsschicht gehört
// processEvent vom Modul wird als Callback aufgerufen
// Daten empfangen (tut nichts, wenn keine Daten vorhanden)
Expand All @@ -817,10 +828,11 @@ void HBWDevice::loop()
// send announce message, if not done yet
handleBroadcastAnnounce();
// feedback from switches and handle keys
for(uint8_t i = 0; i < numChannels; i++)
for(uint8_t i = 0; i < numChannels; i++) {
channels[i]->loop(this,i);
}
// config Button
handleConfigButton();
handleConfigButton();
};


Expand Down
5 changes: 3 additions & 2 deletions libraries/HBWired/HBWired.h
Expand Up @@ -17,7 +17,8 @@ class HBWChannel {
public:
virtual void set(HBWDevice*, uint8_t length, uint8_t const * const data);
virtual uint8_t get(uint8_t* data); // returns length, data must be big enough
virtual void loop(HBWDevice*, uint8_t channel); // channel for feedbacks etc.
virtual void loop(HBWDevice*, uint8_t channel); // channel for feedbacks etc.
virtual void afterReadConfig();
};


Expand Down Expand Up @@ -190,7 +191,7 @@ class HBWDevice {

void factoryReset();
void handleConfigButton();

boolean afterReadConfigPending;
};


Expand Down

0 comments on commit 2fe9cba

Please sign in to comment.