This commit is contained in:
Jens Noack 2021-12-08 18:25:51 +01:00
parent 2f17318f48
commit f56ee193d0
11 changed files with 944 additions and 187 deletions

Binary file not shown.

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 125 KiB

View File

@ -13,6 +13,7 @@ private:
SSD1306Wire * _display;
uint8_t _dispaddr;
int _pin_sda, _pin_scl;
bool _screen_flipped;
public:
display(uint8_t dispaddr, int pin_sda, int pin_scl);
~display();
@ -24,6 +25,8 @@ public:
void data(unsigned int x, unsigned int y ,bool valid, String val, String valname, unsigned int digits, String valunit);
void show();
void clear();
void flipScreenVert();
void setBrigthness(uint8_t value);
};
@ -44,6 +47,7 @@ void display::init()
//initialise OLED and display Welcome Message ...
_display->init();
_display->flipScreenVertically();
_screen_flipped = true;
_display->setTextAlignment(TEXT_ALIGN_CENTER);
_display->setFont(Roboto_Condensed_Bold_16);
_display->clear();
@ -144,4 +148,24 @@ void display::clear()
_display->clear();
}
void display::flipScreenVert()
{
if(_screen_flipped == true)
{
_screen_flipped = false;
_display->invertDisplay();
}
else
{
_screen_flipped = true;
_display->normalDisplay();
//_display->flipScreenVertically();
}
}
void display::setBrigthness(uint8_t value)
{
_display->setBrightness(value);
}
#endif

View File

@ -22,8 +22,8 @@ class leds
unsigned int _pixel_nr = 0;
unsigned int _pixel_last, _pixel_first;
_pixel *_pixels;
uint16_t * _state_flag;
uint16_t _state_mask;
uint32_t * _state_flag;
uint32_t _state_mask;
int _fadestep = 0;
unsigned long _last_faded_ms = 0;
bool _fading_done = false;
@ -47,8 +47,12 @@ class leds
public:
leds(Adafruit_NeoPixel * stripe, uint16_t * state_flag, uint16_t state_mask, uint16_t H, uint8_t S, unsigned int pixel_first, unsigned int pixel_last );
enum led_update {UP_RAINBOW = 1, UP_FADE = 2};
leds(Adafruit_NeoPixel * stripe, uint32_t * state_flag, uint16_t state_mask, uint16_t H, uint8_t S, unsigned int pixel_first, unsigned int pixel_last );
~leds();
bool update();
bool update(led_update type);
void clear();
bool colorWipe( uint32_t color );
void add_button_id(uint16_t mask);
@ -59,9 +63,10 @@ class leds
void setHS(uint16_t H, uint8_t S);
void setColor(uint32_t color);
void rainbowCycle();
bool do_rainbowCycle();
};
leds::leds(Adafruit_NeoPixel * stripe, uint16_t * state_flag, uint16_t state_mask, uint16_t H, uint8_t S, unsigned int pixel_first, unsigned int pixel_last )
leds::leds(Adafruit_NeoPixel * stripe, uint32_t * state_flag, uint16_t state_mask, uint16_t H, uint8_t S, unsigned int pixel_first, unsigned int pixel_last )
{
_state_flag = state_flag;
_state_mask = state_mask;
@ -84,8 +89,6 @@ leds::leds(Adafruit_NeoPixel * stripe, uint16_t * state_flag, uint16_t state_mas
_rainbow_color = 0;
_prev_state = *_state_flag;
_fading_done = true;
}
leds::~leds()
@ -123,6 +126,43 @@ void leds::add_button_id(uint16_t id)
_state_mask = _state_mask | id;
}
bool leds::update()
{
return(update(UP_FADE));
}
bool leds::update(led_update type)
{
if(type == UP_RAINBOW )
{
return(do_rainbowCycle());
}
if(type == UP_FADE)
{
return(do_fade());
}
return(false);
}
bool leds::do_rainbowCycle()
{
bool updated = false;
uint16_t curr_state = _state_mask & *_state_flag;
if(curr_state == 0)
{
clear();
}
else
{
rainbowCycle();
updated = true;
}
return(updated);
}
bool leds::do_fade()
{
bool updated = false;

View File

@ -9,93 +9,95 @@
//#include "eeprom.h"
//eeprom flash;
const unsigned long SZENE_TIMEOUT_TO_SET_TO_DEFAULT_MS = 30000;
///---- OLED ----
const int PIN_MONI_SDA = 21 ; //12
const int PIN_MONI_SCL = 22 ; //14
const uint8_t ADDR_MONI = 0x3c;
display moni(ADDR_MONI, PIN_MONI_SDA, PIN_MONI_SCL);
///---- MP3 ----
const size_t PIN_MP3_RX = 25 ; //D2;
const size_t PIN_MP3_TX = 26 ; //D3;
const uint8_t SONG_EINE_INSEL = 1;
const uint8_t SONG_WEIHNACHTSBAECKEREI = 2;
const uint8_t SONG_WEIHNACHTSBAHN = 3;
const uint8_t SONG_OH_TANNEBAUM = 4;
const uint8_t SONG_DISCO_MARYSBOYCHILD = 5;
const uint8_t SONG_DISCO_LASTCHRISTMAS = 6;
const uint8_t SONG_DISCO_DOTHEYKNOWITSCHRISTMAS = 7;
mp3 mp3ply(PIN_MP3_RX, PIN_MP3_TX);
///---- RELAIS ----
const size_t PIN_RELAIS_HAUESER = 5;
const size_t PIN_RELAIS_STERNE = 17;
const size_t PIN_RELAIS_SPIEGELBALL = 16;
const size_t PIN_RELAIS_OTHER = 4;
relais relais_haeuser(PIN_RELAIS_HAUESER);
relais relais_sterne(PIN_RELAIS_STERNE);
relais relais_spiegel(PIN_RELAIS_SPIEGELBALL);
relais relais_other(PIN_RELAIS_OTHER);
enum relais_t {RNONE = 0, RZUGOBEN=1, RZUGUNTEN=2, RWOLKE=4, RSPIEGEL=8};
const size_t PIN_RELAIS_0 = 5;
const size_t PIN_RELAIS_1 = 17;
const size_t PIN_RELAIS_2 = 16;
const size_t PIN_RELAIS_3 = 4;
relais relais_wolke_schiene(PIN_RELAIS_2);
relais relais_spiegel(PIN_RELAIS_3);
///---- Spannungsregler
uint32_t spannungsregler_state_flag = 0;
const size_t PIN_TRAIN_UNTEN = 32;
const size_t PIN_TRAIN_OBEN = 33;
const size_t PIN_LICHT = 15; //------------------------
#define PWM_CHANNEL_OBEN 5
#define PWM_CHANNEL_UNTEN 6
train zugunten(PIN_TRAIN_UNTEN, PWM_CHANNEL_UNTEN );
train zugoben(PIN_TRAIN_OBEN, PWM_CHANNEL_OBEN );
#define PWM_CHANNEL_LICHT 7
train zugunten("Zugunten", PIN_TRAIN_UNTEN, PWM_CHANNEL_UNTEN, PIN_RELAIS_1,5);
train zugoben("Zugoben", PIN_TRAIN_OBEN, PWM_CHANNEL_OBEN, PIN_RELAIS_0,5 );
train licht("Licht", PIN_LICHT, PWM_CHANNEL_LICHT, -1 ,5);
///--- IOs ----
const size_t PIN_IO0 = 23;
const size_t PIN_IO1 = 10;
const size_t PIN_IO2 = 9;
const size_t PIN_IO3 = 18;
///--- Taster ----
const size_t PIN_TASTER_AUSSEN_LICHT = 36;
const size_t PIN_TASTER_AUSSEN_MOVE = 39;
const size_t PIN_TASTER_TRAIN_UNTEN = 34;
const size_t PIN_TASTER_TRAIN_OBEN = 35;
const unsigned long BOUNCING_TIME_MS = 300;
unsigned long last_pressed_1, last_pressed_2, last_pressed_3, last_pressed_4;
unsigned long number_pressed_1, number_pressed_2, number_pressed_3, number_pressed_4;
/*
void IRAM_ATTR ISR_1()
{
if(millis()-last_pressed_1 > BOUNCING_TIME_MS)
{
last_pressed_1 = millis();
number_pressed_1 += 1;
}
}
void IRAM_ATTR ISR_2()
{
if(millis()-last_pressed_2 > BOUNCING_TIME_MS)
{
last_pressed_2 = millis();
number_pressed_2 += 1;
}
}
void IRAM_ATTR ISR_3()
{
if(millis()-last_pressed_3 > BOUNCING_TIME_MS)
{
last_pressed_3 = millis();
number_pressed_3 += 1;
}
}
void IRAM_ATTR ISR_4()
{
if(millis()-last_pressed_4 > BOUNCING_TIME_MS)
{
last_pressed_4 = millis();
number_pressed_4 += 1;
}
}
taster taster_aussen_licht(PIN_TASTER_AUSSEN_LICHT, &ISR_1, &number_pressed_1);
taster taster_aussen_move(PIN_TASTER_AUSSEN_MOVE, &ISR_2, &number_pressed_2);
taster taster_train_unten(PIN_TASTER_TRAIN_UNTEN, &ISR_3, &number_pressed_3);
taster taster_train_oben(PIN_TASTER_TRAIN_OBEN, &ISR_4, &number_pressed_4);
*/
const size_t PIN_TASTER_AUSSEN_LICHT = 36;
const size_t PIN_TASTER_AUSSEN_MOVE = 39; //-----------------
const size_t PIN_TASTER_TRAIN_UNTEN = 35;
const size_t PIN_TASTER_TRAIN_OBEN = 13;
taster taster_aussen_licht(PIN_TASTER_AUSSEN_LICHT);
taster taster_aussen_move(PIN_TASTER_AUSSEN_MOVE);
taster taster_train_unten(PIN_TASTER_TRAIN_UNTEN);
taster taster_train_oben(PIN_TASTER_TRAIN_OBEN);
///--- RGB LEDs ---
uint16_t rgbled_state_flag = 0;
const size_t PIN_RGBLEDS = 19;
#define NUMRGBLEDS 25
Adafruit_NeoPixel rgb_leds(NUMRGBLEDS, PIN_RGBLEDS, NEO_GRB + NEO_KHZ800);
taster taster_schiene(PIN_IO0);
enum led_t {LTANNE=1, LBACK=2, LSTERNE=4, LTEICH=8};
leds led_tanne(&rgb_leds, &rgbled_state_flag, LTANNE, 5000,220, 0, 5 );
leds led_teich(&rgb_leds, &rgbled_state_flag, LTEICH, 5000,220, 6, 10 );
leds led_sterne(&rgb_leds, &rgbled_state_flag, LSTERNE, 5000,220, 11, 24 );
///--- RGB LEDs ---
uint32_t licht_state_flag = 0;
const size_t PIN_RGBLEDS = 19;
#define NUMRGBLEDS 109
Adafruit_NeoPixel rgb_leds(NUMRGBLEDS, PIN_RGBLEDS, NEO_GRB + NEO_KHZ800);
enum led_t {LTANNE=1, LBACK=2, LBAUHOF=4, LTEICH=8, LBURG=16, LSTERNE1=32, LSTERNE2=64, LSTERNBILD1 = 128, LSTERNBILD2=256, LSTERNBILD3=512, LHAEUSER=1024, LSPIEGEL=2048};
leds led_back(&rgb_leds, &licht_state_flag, LBACK, 5000,220, 0, 6 );
leds led_burg(&rgb_leds, &licht_state_flag, LBURG, 5000,220, 7, 9);
leds led_teich(&rgb_leds, &licht_state_flag, LTEICH, 5000,220, 10, 16 );
leds led_sternbilder1(&rgb_leds, &licht_state_flag, LSTERNBILD1, 5000,220, 17, 17 );
leds led_sterne1(&rgb_leds, &licht_state_flag, LSTERNE1, 5000,220, 18, 18 );
leds led_sternbilder2(&rgb_leds, &licht_state_flag, LSTERNBILD2, 5000,220, 19, 19 );
leds led_sterne2(&rgb_leds, &licht_state_flag, LSTERNE2, 5000,220, 20, 20 );
leds led_sternbilder3(&rgb_leds, &licht_state_flag, LSTERNBILD3, 5000,220, 21, 21 );
leds led_bauhof(&rgb_leds, &licht_state_flag, LBAUHOF, 5000,220, 22, 24);
leds led_tanne(&rgb_leds, &licht_state_flag, LTANNE, 5000,220, 25, 25 );
/*
leds led_back(&rgb_leds, &licht_state_flag, LBACK, 5000,220, 0, 69 );
leds led_burg(&rgb_leds, &licht_state_flag, LBURG, 5000,220, 70, 76);
leds led_teich(&rgb_leds, &licht_state_flag, LTEICH, 5000,220, 77, 88 );
leds led_sternbilder1(&rgb_leds, &licht_state_flag, LSTERNBILD1, 5000,220, 89, 90 );
leds led_sterne1(&rgb_leds, &licht_state_flag, LSTERNE1, 5000,220, 91, 92 );
leds led_sternbilder2(&rgb_leds, &licht_state_flag, LSTERNBILD2, 5000,220, 93, 94 );
leds led_sterne2(&rgb_leds, &licht_state_flag, LSTERNE2, 5000,220, 95, 96 );
leds led_sternbilder3(&rgb_leds, &licht_state_flag, LSTERNBILD3, 5000,220, 97, 98 );
leds led_bauhof(&rgb_leds, &licht_state_flag, LBAUHOF, 5000,220, 99, 106);
leds led_tanne(&rgb_leds, &licht_state_flag, LTANNE, 5000,220, 107, 108 );
*/

View File

@ -6,16 +6,33 @@
class mp3
{
private:
const byte FADESTEP_WITH = 5;
const char* STARTED_STRING = "Status: playing";
const char* STOPPED_STRING = "Status: stopped";
SerialMP3Player *player;
size_t _rx_pin,_tx_pin;
unsigned long _play_since_ms = 0;
const byte _MAX_FADE_STEP = 255;
const byte _MIN_FADE_STEP = 0;
byte _current_max_fade_step;
byte _current_min_fade_step;
static const unsigned long _FADE_DELAY_MS = 10;
byte _fade_step;
unsigned long _last_faded_ms;
unsigned long _delay_ms;
bool _fade(bool fade_up);
void _vol(byte val);
public:
mp3(size_t rx_pin, size_t tx_pin);
~mp3();
void stop();
bool fade_out();
bool fade_in();
void play(size_t nr);
unsigned long is_playing();
void begin(byte vol=30);
@ -28,6 +45,11 @@ mp3::mp3(size_t rx_pin, size_t tx_pin)
_rx_pin = rx_pin;
_tx_pin = tx_pin;
player = new SerialMP3Player(_rx_pin, _tx_pin);
_fade_step = 0;
_last_faded_ms = 0;
_delay_ms = _FADE_DELAY_MS;
_current_max_fade_step = _MAX_FADE_STEP;
_current_min_fade_step = _MIN_FADE_STEP;
}
mp3::~mp3()
@ -36,6 +58,7 @@ mp3::~mp3()
void mp3::begin(byte vol)
{
_current_max_fade_step = vol;
player->begin(9600);
delay(500);
player->sendCommand(CMD_SEL_DEV, 0, 2); //select sd-card
@ -45,7 +68,8 @@ void mp3::begin(byte vol)
void mp3::play_vol(size_t nr, byte vol)
{
player->setVol(vol);
_current_max_fade_step = vol;
_vol(vol);
player->play(nr);
_play_since_ms = millis();
}
@ -59,10 +83,18 @@ void mp3::play(size_t nr)
void mp3::vol(byte val)
{
player->setVol(val);
_play_since_ms = millis();
_current_max_fade_step = val;
_vol(val);
}
void mp3::_vol(byte val)
{
_fade_step = val;
Serial.printf("MP3 players volume set to %d.\n", val);
player->setVol(val);
}
unsigned long mp3::is_playing()
{
player->qStatus();
@ -73,6 +105,7 @@ unsigned long mp3::is_playing()
return(millis() - _play_since_ms);
}
}
Serial.printf("MP3 Player is not playing\n");
return 0;
}
@ -81,4 +114,54 @@ void mp3::stop()
player->stop();
}
bool mp3::_fade(bool fade_up)
{
if(millis() - _last_faded_ms > _delay_ms)
{
_last_faded_ms = millis();
if(true == fade_up)
{
if(_current_max_fade_step > _fade_step)
{
if(_fade_step + FADESTEP_WITH > _current_max_fade_step)
_fade_step = _current_max_fade_step;
else
_fade_step = FADESTEP_WITH + _fade_step;
_fade_step = _fade_step + FADESTEP_WITH;
}
else
return false;
}
else
{
if(_current_min_fade_step < _fade_step)
if(_fade_step - FADESTEP_WITH < _current_min_fade_step)
_fade_step = _current_min_fade_step;
else
_fade_step = _fade_step - FADESTEP_WITH;
else
return false;
}
_vol(_fade_step);
}
return true;
}
bool mp3::fade_out()
{
if(_fade(false) == true)
return(true);
else
{
player->stop();
return(false);
}
}
bool mp3::fade_in()
{
return(_fade(true));
}
#endif

View File

@ -15,14 +15,20 @@ public:
void off();
void toggle();
bool is_on();
void begin();
};
relais::relais(size_t ctrl_pin)
{
_ctrl_pin = ctrl_pin;
_relais_on = false;
}
void relais::begin()
{
pinMode(_ctrl_pin, OUTPUT);
off();
digitalWrite(_ctrl_pin, HIGH);
_relais_on = false;
}
relais::~relais()
@ -31,14 +37,20 @@ relais::~relais()
void relais::on()
{
digitalWrite(_ctrl_pin, LOW);
_relais_on = true;
if(_relais_on == false)
{
digitalWrite(_ctrl_pin, LOW);
_relais_on = true;
}
}
void relais::off()
{
digitalWrite(_ctrl_pin, HIGH);
_relais_on = false;
if(_relais_on == true)
{
digitalWrite(_ctrl_pin, HIGH);
_relais_on = false;
}
}
void relais::toggle()

View File

@ -11,7 +11,7 @@ private:
unsigned long _number_pressed;
unsigned long _number_checked;
size_t _taster_pin;
//unsigned long * _ptr_number_pressed;
volatile unsigned long * _ptr_number_pressed;
void IRAM_ATTR _taster_int()
{
@ -24,13 +24,15 @@ private:
}
public:
//taster(const size_t pin, void (*isrfunction)(), unsigned long* ptr_number_pressed);
//taster(const size_t pin, volatile unsigned long* ptr_number_pressed);
taster(const size_t pin);
~taster();
bool pressed();
void reset();
void begin();
};
//taster::taster(size_t pin, void (*isrfunction)(), unsigned long* ptr_number_pressed)
//taster::taster(size_t pin, volatile unsigned long* ptr_number_pressed)
taster::taster(size_t pin)
{
_taster_pin = pin;
@ -38,23 +40,33 @@ taster::taster(size_t pin)
_number_checked = 0;
_number_pressed = 0;
_last_pressed = 0;
pinMode(_taster_pin, INPUT);
}
void taster::begin()
{
pinMode(_taster_pin, INPUT_PULLUP);
attachInterrupt(_taster_pin, std::bind(&taster::_taster_int,this), FALLING);
//attachInterrupt(_taster_pin, isrfunction, FALLING);
}
taster::~taster()
{
detachInterrupt(_taster_pin);
//detachInterrupt(_taster_pin);
}
bool taster::pressed() {
if (_number_pressed != _number_checked)
//if (*_ptr_number_pressed > _number_checked)
if (_number_pressed > _number_checked)
{
//_number_checked = *_ptr_number_pressed;
_number_checked = _number_pressed;
return true;
}
return false;
}
void taster::reset() {
_number_pressed = _number_checked;
}
#endif

View File

@ -9,9 +9,15 @@ class train
private:
const uint8_t _MAX_FADE_STEP = 255;
const uint8_t _MIN_FADE_STEP = 0;
uint8_t _current_max_fade_step;
uint8_t _current_min_fade_step;
static const unsigned long _FADE_DELAY_MS = 50;
size_t _relais_pin;
const char* _name;
bool _switch_zero_relais;
uint8_t _prev_pwm_value = 255;
size_t _pwmpin;
size_t _pwmchannel;
uint8_t _fade_step;
@ -21,25 +27,47 @@ private:
bool _fade(bool fade_up);
public:
train(size_t pwmpin , size_t pwmchannel,unsigned long delay_ms = _FADE_DELAY_MS);
train(const char* name, size_t pwmpin , size_t pwmchannel, size_t relais_pin, unsigned long delay_ms = _FADE_DELAY_MS);
~train();
void stop();
bool fade_on();
bool fade_off();
void set_pwm(uint8_t pwm_value);
void begin();
bool is_stopped();
bool is_up();
bool is_down();
uint8_t get_pwm();
void switch_zero_relais(bool do_switch);
bool fade_down_to(uint8_t pwm_value);
bool fade_up_to(uint8_t pwm_value);
};
train::train(size_t pwmpin, size_t pwmchannel, unsigned long delay_ms)
train::train(const char* name, size_t pwmpin, size_t pwmchannel, size_t relais_pin, unsigned long delay_ms)
{
_pwmpin = pwmpin;
_pwmchannel = pwmchannel;
_fade_step = 0;
_last_faded_ms = 0;
_delay_ms = delay_ms;
ledcSetup(pwmchannel, 100, 8);
ledcAttachPin(_pwmpin, pwmchannel);
_relais_pin = relais_pin;
_name = name;
_switch_zero_relais = true;
_current_max_fade_step = _MAX_FADE_STEP;
_current_min_fade_step = _MIN_FADE_STEP;
}
void train::begin()
{
//pinMode(_pwmpin, OUTPUT);
ledcSetup(_pwmchannel, 100, 8);
ledcAttachPin(_pwmpin, _pwmchannel);
if(_relais_pin != -1)
{
pinMode(_relais_pin, OUTPUT);
digitalWrite(_relais_pin, HIGH);
}
}
train::~train()
@ -47,7 +75,25 @@ train::~train()
}
void train::set_pwm(uint8_t pwm_value) {
ledcWrite(_pwmchannel, pwm_value);
if(_prev_pwm_value != pwm_value)
{
_prev_pwm_value = pwm_value;
if(_relais_pin != -1 )
{
if(pwm_value == 0 )
{
if( _switch_zero_relais == true)
digitalWrite(_relais_pin, HIGH);
}
else
{
digitalWrite(_relais_pin, LOW);
}
}
_fade_step = pwm_value;
ledcWrite(_pwmchannel, pwm_value);
Serial.printf("PWM '%s' set to value %d\n", _name, pwm_value);
}
}
void train::stop() {
@ -61,31 +107,83 @@ bool train::_fade(bool fade_up)
_last_faded_ms = millis();
if(true == fade_up)
{
if(_MAX_FADE_STEP > _fade_step)
if(_current_max_fade_step > _fade_step)
{
_fade_step++;
}
else
return false;
}
else
{
if(_MIN_FADE_STEP < _fade_step)
if(_current_min_fade_step < _fade_step)
_fade_step--;
else
return false;
}
set_pwm(_fade_step);
}
return true;
}
bool train::fade_down_to(uint8_t pwm_value)
{
_current_min_fade_step = pwm_value;
return _fade(false);
}
bool train::fade_up_to(uint8_t pwm_value)
{
_current_max_fade_step = pwm_value;
return _fade(true);
}
bool train::fade_on()
{
_current_max_fade_step = _MAX_FADE_STEP;
return _fade(true);
}
bool train::fade_off()
{
_current_min_fade_step = _MIN_FADE_STEP;
return _fade(false);
}
void train::switch_zero_relais(bool do_switch)
{
_switch_zero_relais = do_switch;
}
bool train::is_stopped()
{
if(_prev_pwm_value == 0)
return true;
else
return false;
}
bool train::is_up()
{
if(_prev_pwm_value == _current_max_fade_step)
return true;
else
return false;
}
bool train::is_down()
{
if(_prev_pwm_value == _current_min_fade_step)
return true;
else
return false;
}
uint8_t train::get_pwm()
{
return _prev_pwm_value;
}
#endif

View File

@ -1,121 +1,607 @@
#include "main.h"
//funtion prototypes
void show_counters(uint64_t counter_licht, uint64_t counter_move);
void taster_abfrage();
void set_lichtszene();
void set_moveszene();
bool licht_update();
void szene_oh_tannebaum();
void szene_nachts_dorf();
void szene_schnee_dorf();
void szene_nachts();
void szene_tag_dorf();
void move_zugoben();
void move_zugunten();
void move_schiene_oben();
void show_counters();
void updateNVS();
//variables
uint16_t licht_all_count = 0;
uint16_t move_all_count = 0;
unsigned int licht_all_count = 0;
unsigned int move_all_count = 0;
unsigned long last_updated_NVS = 0;
bool licht_is_fading = false;
void setup() {
Serial.begin(115200);
rgb_leds.begin();
taster_aussen_licht.begin();
taster_aussen_move.begin();
taster_train_unten.begin();
taster_train_oben.begin();
taster_schiene.begin();
relais_wolke_schiene.begin();
relais_spiegel.begin();
zugoben.begin();
zugunten.begin();
licht.begin();
NVS.begin();
moni.init();
//load counters
//NVS.setInt("licht", 100);
//NVS.setInt("move", 50);
licht_all_count = NVS.getInt("licht");
move_all_count = NVS.getInt("move");
// all relais off;
relais_haeuser.off();
relais_sterne.off();
relais_spiegel.off();
relais_other.off();
zugoben.stop();
zugunten.stop();
led_tanne.setColor(rgb_leds.Color(0, 150, 0));
rgbled_state_flag = rgbled_state_flag | LSTERNE;
moni.init();
moni.setBrigthness(100);
licht_state_flag = LSTERNBILD1 | LSTERNBILD2 | LSTERNBILD3 | LSTERNE1 | LSTERNE2 | LBAUHOF | LBURG | LTANNE;
mp3ply.begin();
mp3ply.stop();
led_sterne1.setBrigthness(20);
led_sterne2.setBrigthness(20);
led_sternbilder1.setBrigthness(220);
led_sternbilder2.setBrigthness(220);
led_sternbilder3.setBrigthness(220);
led_bauhof.setBrigthness(40);
led_burg.setBrigthness(40);
led_teich.setBrigthness(1);
led_back.setBrigthness(200);
//blau led_back.setHS(32000,200);
led_back.setHS(9000,180);
led_teich.setHS(40000,255);
}
uint8_t licht_count = 0;
bool faded_on = false;
void loop() {
if(faded_on == false)
updateNVS();
show_counters();
taster_abfrage();
set_lichtszene();
set_moveszene();
licht_is_fading = licht_update();
}
bool next_licht_szene_possible = true;
bool next_move_szene_possible = true;
uint8_t licht_szene = 0;
uint8_t move_szene = 0;
unsigned long szene_time_ms = 0;
unsigned long szene_overall_time_ms = 0;
void set_lichtszene()
{
if(next_licht_szene_possible == false)
{
if(true == led_sterne.fade_on())
faded_on = true;
szene_overall_time_ms = millis();
switch(licht_szene)
{
case 0:
szene_nachts();
break;
case 1:
szene_nachts_dorf();
break;
case 2:
szene_schnee_dorf();
break;
case 3:
szene_tag_dorf();
break;
case 4:
szene_oh_tannebaum();
break;
default:
licht_szene = 0;
}
}
if(millis() - szene_overall_time_ms > SZENE_TIMEOUT_TO_SET_TO_DEFAULT_MS)
{
licht_state_flag = LSTERNBILD1 | LSTERNBILD2 | LSTERNBILD3 | LSTERNE1 | LSTERNE2 | LTANNE;
licht_szene = 0;
taster_aussen_licht.reset();
next_licht_szene_possible = true;
}
}
void set_moveszene()
{
if(next_move_szene_possible == false)
{
switch(move_szene)
{
case 0:
move_zugoben();
break;
case 1:
move_zugunten();
break;
case 2:
move_schiene_oben();
break;
default:
move_szene = 0;
break;
}
}
}
const byte TANNENBAUM_VOL = 20;
const unsigned long TANNENBAUM_PLAY_MUSIC_MS = 60000;
typedef enum {TA_INIT = 0, TA_LIGHT_READY, TA_START_PLAYING ,TA_MIN_PLAYING,TA_PLAYING, TA_STOP_PLAYING, TA_FINSIHED} szene_tanne_t;
szene_tanne_t tanne_state = TA_INIT;
void szene_oh_tannebaum()
{
unsigned long msecs = millis();
switch(tanne_state)
{
case TA_INIT:
Serial.printf("Tannenbaum spielt\n");
licht_state_flag = LSTERNBILD1 | LSTERNBILD2 | LSTERNBILD3 | LSTERNE1 | LSTERNE2 | LTANNE;
tanne_state = TA_LIGHT_READY;
break;
case TA_LIGHT_READY:
if(licht_is_fading == false)
{
tanne_state = TA_START_PLAYING;
Serial.printf("All lights are ready for Oh Tannebaum\n");
mp3ply.play_vol(2, TANNENBAUM_VOL);
}
break;
case TA_START_PLAYING:
szene_time_ms = msecs;
if(mp3ply.is_playing() > 0)
{
tanne_state = TA_MIN_PLAYING;
Serial.printf("Oh Tannebaum is playing\n");
}
break;
case TA_MIN_PLAYING:
taster_aussen_licht.reset();
if(msecs - szene_time_ms > 1000)
tanne_state = TA_PLAYING;
break;
case TA_PLAYING:
if(msecs - szene_time_ms > TANNENBAUM_PLAY_MUSIC_MS || taster_aussen_licht.pressed() == true || mp3ply.is_playing() == 0)
tanne_state = TA_STOP_PLAYING;
break;
case TA_STOP_PLAYING:
if(mp3ply.fade_out() == false)
{
//if(mp3ply.is_playing() == 0)
//{
Serial.printf("Oh Tannebaum faded out and stopped\n");
tanne_state = TA_FINSIHED;
//}
}
break;
case TA_FINSIHED:
tanne_state = TA_INIT;
next_licht_szene_possible = true;
//taster_aussen_licht.reset();
Serial.printf("Tannenbaum finished\n");
break;
}
}
typedef enum {NA_INIT = 0, NA_LIGHT_READY, NA_FINISHED} szene_nacht_t;
szene_nacht_t nacht_state = NA_INIT;
void szene_nachts_dorf()
{
switch(nacht_state)
{
case NA_INIT:
Serial.printf("Nachts im Dorf\n");
licht_state_flag = LSTERNBILD1 | LSTERNBILD2 | LSTERNBILD3 | LSTERNE1 | LSTERNE2 | LTANNE | LBURG | LBAUHOF | LTEICH | LHAEUSER;
nacht_state = NA_LIGHT_READY;
break;
case NA_LIGHT_READY:
if(licht_is_fading == false)
{
nacht_state = NA_FINISHED;
Serial.printf("All lights are ready for Nachts im Dorf\n");
}
break;
case NA_FINISHED:
nacht_state = NA_INIT;
next_licht_szene_possible = true;
taster_aussen_licht.reset();
Serial.printf("Nachts im Dorf finished\n");
break;
}
}
typedef enum {SD_INIT = 0, SD_LIGHT_READY, SD_FINISHED} szene_schnee_t;
szene_schnee_t schnee_state = SD_INIT;
void szene_schnee_dorf()
{
switch(schnee_state)
{
case SD_INIT:
Serial.printf("Schnee im Dorf\n");
licht_state_flag = LSTERNE1 | LSTERNE2 | LTANNE | LBURG | LBAUHOF | LTEICH | LSPIEGEL | LHAEUSER;
schnee_state = SD_LIGHT_READY;
break;
case SD_LIGHT_READY:
if(licht_is_fading == false)
{
schnee_state = SD_FINISHED;
Serial.printf("All lights are ready for Schnee im Dorf\n");
}
break;
case SD_FINISHED:
schnee_state = SD_INIT;
next_licht_szene_possible = true;
taster_aussen_licht.reset();
Serial.printf("Schnee im Dorf finished\n");
break;
}
}
typedef enum {DU_INIT = 0, DU_LIGHT_READY, DU_FINISHED} szene_dunkel_t;
szene_dunkel_t dunkel_state = DU_INIT;
void szene_nachts()
{
switch(dunkel_state)
{
case DU_INIT:
Serial.printf("Dunkel im Dorf\n");
licht_state_flag = LSTERNBILD1 | LSTERNBILD2 | LSTERNBILD3 | LSTERNE1 | LSTERNE2;
dunkel_state = DU_LIGHT_READY;
break;
case DU_LIGHT_READY:
if(licht_is_fading == false)
{
dunkel_state = DU_FINISHED;
Serial.printf("All lights are ready for Dunkel im Dorf\n");
}
break;
case DU_FINISHED:
dunkel_state = DU_INIT;
next_licht_szene_possible = true;
taster_aussen_licht.reset();
Serial.printf("Dunkel im Dorf finished\n");
break;
}
}
typedef enum {TAG_INIT = 0, TAG_LIGHT_READY, TAG_FINISHED} szene_tag_t;
szene_tag_t tag_state = TAG_INIT;
void szene_tag_dorf()
{
switch(tag_state)
{
case TAG_INIT:
Serial.printf("Tag im Dorf\n");
licht_state_flag = LTANNE | LBACK;
tag_state = TAG_LIGHT_READY;
break;
case TAG_LIGHT_READY:
if(licht_is_fading == false)
{
tag_state = TAG_FINISHED;
Serial.printf("All lights are ready for Tag im Dorf\n");
}
break;
case TAG_FINISHED:
tag_state = TAG_INIT;
next_licht_szene_possible = true;
taster_aussen_licht.reset();
Serial.printf("Tag im Dorf finished\n");
break;
}
}
unsigned int zugunten_error = 0;
const unsigned int ZUGUNTEN_MAX_ERROR_COUNT = 5;
const unsigned long ZUGUNTEN_DRIVES_TO_STATION_MS = 5000;
const unsigned long ZUGUNTEN_STOPPED_AT_STATION_MS = 5000;
const unsigned long ZUGUNTEN_MAX_TIME_TO_HOME_MS = 15000; ///timeout time
typedef enum {ZU_INIT = 0, ZU_AT_HOME , ZU_DRIVES_TO_STATION, ZU_STOPPES_AT_STATION, ZU_STOPPED_AT_STATION, ZU_DRIVES_HOME, ZU_STOPPES_AT_HOME} szene_zugunten_t;
szene_zugunten_t zugunten_state = ZU_INIT;
void move_zugunten()
{
unsigned long msecs = millis();
switch(zugunten_state)
{
case ZU_INIT:
Serial.printf("Zugunten fährt\n");
taster_train_unten.reset();
if (zugunten_error > ZUGUNTEN_MAX_ERROR_COUNT)
zugunten_state = ZU_STOPPES_AT_HOME;
else
zugunten_state = ZU_AT_HOME;
break;
case ZU_AT_HOME:
szene_time_ms = msecs;
if(zugunten.fade_on() == false)
zugunten_state = ZU_DRIVES_TO_STATION;
break;
case ZU_DRIVES_TO_STATION:
if(msecs - szene_time_ms > ZUGUNTEN_DRIVES_TO_STATION_MS)
{
zugunten_state = ZU_STOPPES_AT_STATION;
zugunten.switch_zero_relais(false);
}
break;
case ZU_STOPPES_AT_STATION:
szene_time_ms = msecs;
if(zugunten.fade_off() == false)
zugunten_state = ZU_STOPPED_AT_STATION;
break;
case ZU_STOPPED_AT_STATION:
if(msecs - szene_time_ms > ZUGUNTEN_STOPPED_AT_STATION_MS)
{
zugunten_state = ZU_DRIVES_HOME;
szene_time_ms = msecs;
}
break;
case ZU_DRIVES_HOME:
if(zugunten.fade_on() == false)
if(taster_train_unten.pressed() == true || (msecs-szene_time_ms) > ZUGUNTEN_MAX_TIME_TO_HOME_MS)
{
if( (msecs-szene_time_ms) > ZUGUNTEN_MAX_TIME_TO_HOME_MS)
{
Serial.printf("Train unten runs ins timeout while driving back at Home\n");
zugunten_error++;
}
else{
Serial.printf("Train unten back at Home pressed\n");
zugunten_error = 0;
}
zugunten_state = ZU_STOPPES_AT_HOME;
zugunten.switch_zero_relais(true);
}
break;
case ZU_STOPPES_AT_HOME:
if(zugunten.fade_off() == false)
{
zugunten_state = ZU_INIT;
next_move_szene_possible = true;
taster_aussen_move.reset();
Serial.printf("Zugunten stopped\n");
}
break;
}
}
unsigned int zugoben_error = 0;
const unsigned int ZUGOBEN_MAX_ERROR_COUNT = 5;
const unsigned long ZUGOBEN_DRIVES_TO_BRIDGE_MS = 2000;
const unsigned long ZUGOBEN_DRIVES_ON_BRIDGE_MS = 2000;
const unsigned long ZUGOBEN_MAX_TIME_TO_HOME_MS = 10000; ///timeout time
const uint8_t ZUGOBEN_SPEED_ON_BRIDGE = 80;
typedef enum {ZO_INIT = 0, ZO_AT_HOME, ZO_DRIVES_TO_BRIDGE, ZO_DRIVES_SLOWDOWN_ON_BRIDGE, ZO_DRIVES_ON_BRIDGE, ZO_DRIVES_HOME, ZO_STOPPES_AT_HOME} szene_zugoben_t;
szene_zugoben_t zugoben_state = ZO_INIT;
void move_zugoben()
{
unsigned long msecs = millis();
switch(zugoben_state)
{
case ZO_INIT:
Serial.printf("Zugoben fährt\n");
taster_train_oben.reset();
if (zugoben_error > ZUGOBEN_MAX_ERROR_COUNT)
zugoben_state = ZO_STOPPES_AT_HOME;
else
zugoben_state = ZO_AT_HOME;
break;
case ZO_AT_HOME:
szene_time_ms = msecs;
if(zugoben.fade_on() == false)
zugoben_state = ZO_DRIVES_TO_BRIDGE;
break;
case ZO_DRIVES_TO_BRIDGE:
if(msecs - szene_time_ms > ZUGOBEN_DRIVES_TO_BRIDGE_MS)
zugoben_state = ZO_DRIVES_SLOWDOWN_ON_BRIDGE;
break;
case ZO_DRIVES_SLOWDOWN_ON_BRIDGE:
szene_time_ms = msecs;
if(zugoben.fade_down_to(ZUGOBEN_SPEED_ON_BRIDGE) == false)
zugoben_state = ZO_DRIVES_ON_BRIDGE;
break;
case ZO_DRIVES_ON_BRIDGE:
if(msecs - szene_time_ms > ZUGOBEN_DRIVES_ON_BRIDGE_MS)
{
zugoben_state = ZO_DRIVES_HOME;
szene_time_ms = msecs;
}
break;
case ZO_DRIVES_HOME:
if(zugoben.fade_on() == false)
if(taster_train_oben.pressed() == true || (msecs-szene_time_ms) > ZUGOBEN_MAX_TIME_TO_HOME_MS)
{
if((msecs-szene_time_ms) > ZUGOBEN_MAX_TIME_TO_HOME_MS)
{
Serial.printf("Train oben runs in time out while driving back at home\n");
zugoben_error++;
}
else
{
Serial.printf("Train oben back at Home pressed\n");
zugoben_error = 0;
}
zugoben_state = ZO_STOPPES_AT_HOME;
}
break;
case ZO_STOPPES_AT_HOME:
if(zugoben.fade_off() == false)
{
zugoben_state = ZO_INIT;
next_move_szene_possible = true;
taster_aussen_move.reset();
Serial.printf("Zugoben stopped at home\n");
}
break;
}
}
unsigned int soben_error = 0;
const unsigned int SOBEN_MAX_ERROR_COUNT = 5;
const unsigned long SOBEN_MAX_DRIVES_TIME_MS = 30000; ///timeout time
typedef enum {SO_INIT = 0, SO_AT_HOME, SO_DRIVES_HOME, SO_STOPPES_AT_HOME} szene_soben_t;
szene_soben_t soben_state = SO_INIT;
void move_schiene_oben()
{
unsigned long msecs = millis();
switch(soben_state)
{
case SO_INIT:
Serial.printf("Schiene oben fährt\n");
taster_schiene.reset();
if(soben_error > SOBEN_MAX_ERROR_COUNT)
soben_state = SO_STOPPES_AT_HOME;
else
soben_state = SO_AT_HOME;
break;
case SO_AT_HOME:
szene_time_ms = millis();
relais_wolke_schiene.on();
soben_state = SO_DRIVES_HOME;
break;
case SO_DRIVES_HOME:
if(taster_schiene.pressed() == true || (msecs-szene_time_ms) > SOBEN_MAX_DRIVES_TIME_MS)
{
if((msecs-szene_time_ms) > SOBEN_MAX_DRIVES_TIME_MS)
{
soben_error++;
Serial.printf("Schiene oben timeout while driving home.\n");
}
else
{
soben_error = 0;
Serial.printf("Schiene oben back at Home pressed\n");
}
soben_state = SO_STOPPES_AT_HOME;
}
break;
case SO_STOPPES_AT_HOME:
relais_wolke_schiene.off();
soben_state = SO_INIT;
next_move_szene_possible = true;
taster_aussen_move.reset();
Serial.printf("Schiene oben stopped at home\n");
break;
}
}
bool licht_update()
{
bool fade_updated = false;
bool rainbow_updated = false;
fade_updated = led_sterne1.update() || fade_updated;
fade_updated = led_sterne2.update() || fade_updated;
fade_updated = led_sternbilder1.update() || fade_updated;
fade_updated = led_sternbilder2.update() || fade_updated;
fade_updated = led_sternbilder3.update()|| fade_updated;
rainbow_updated = led_tanne.update(leds::UP_RAINBOW) || rainbow_updated;
fade_updated = led_bauhof.update() || fade_updated;
fade_updated = led_burg.update() || fade_updated;
fade_updated = led_teich.update() || fade_updated;
fade_updated = led_back.update() || fade_updated;
if((licht_state_flag & LHAEUSER) == 0)
{
//Serial.printf("Fade off lights at houses");
fade_updated = licht.fade_off() || fade_updated;
}
else
{
if(true == led_sterne.fade_off())
faded_on = false;
//Serial.printf("Fade on lights at houses");
fade_updated = licht.fade_on() || fade_updated;
}
led_teich.rainbowCycle();
rgb_leds.show();
if(taster_aussen_licht.pressed())
if((licht_state_flag & LSPIEGEL) == 0)
relais_spiegel.off();
else
relais_spiegel.on();
if(true == rainbow_updated || true == fade_updated)
{
relais_haeuser.toggle();
licht_all_count++;
NVS.setInt("licht", licht_all_count);
rgb_leds.show();
}
if(taster_aussen_move.pressed())
{
relais_other.toggle();
move_all_count++;
NVS.setInt("move", move_all_count);
}
if(taster_train_oben.pressed())
relais_sterne.toggle();
if(taster_train_unten.pressed())
relais_spiegel.toggle();
show_counters(licht_all_count, move_all_count);
/*
switch (licht_count)
{
case 1:
haeuser.on();
sterne.off();
spiegel.off();
other.off();
break;
case 2:
haeuser.off();
sterne.on();
spiegel.off();
other.off();
break;
case 3:
haeuser.off();
sterne.off();
spiegel.on();
other.off();
break;
case 4:
haeuser.off();
sterne.off();
spiegel.off();
other.on();
break;
default:
haeuser.off();
sterne.off();
spiegel.off();
other.off();
break;
}
*/
return(fade_updated);
}
void show_counters(uint64_t counter_licht, uint64_t counter_move)
void taster_abfrage()
{
if(next_licht_szene_possible == true)
{
if(taster_aussen_licht.pressed() == true)
{
Serial.printf("Aussenlicht pressed\n");
licht_szene++;
licht_all_count++;
next_licht_szene_possible = false;
}
}
if(next_move_szene_possible == true)
{
if(taster_aussen_move.pressed() == true)
{
Serial.printf("Move pressed\n");
move_szene++;
move_all_count++;
next_move_szene_possible = false;
}
}
}
void updateNVS()
{
static uint8_t value = 0;
if(millis() - last_updated_NVS > 1000)
{
last_updated_NVS = millis();
switch(value)
{
case 1:
NVS.setInt("licht", licht_all_count);
break;
case 2:
NVS.setInt("move", move_all_count);
break;
default:
value = 0;
}
value++;
}
}
unsigned long display_time_ms = 0;
const unsigned long MAX_DISPLAY_TIME_BEFORE_FLIP_MS = 600000;
void show_counters()
{
if(millis() - display_time_ms > MAX_DISPLAY_TIME_BEFORE_FLIP_MS)
{
display_time_ms = millis();
moni.flipScreenVert();
}
moni.clear();
moni.header("Zaehler");
moni.data(30,20,counter_licht, "Licht");
moni.data(100,20,counter_move, "Moves");
moni.data(30,12,(uint64_t)licht_all_count, "Licht");
moni.data(100,12, (uint64_t)move_all_count, "Moves");
moni.data(15,38,(uint64_t)zugunten_error, "ZUErr");
moni.data(60,38,(uint64_t)zugoben_error, "ZOErr");
moni.data(100,38,(uint64_t)soben_error, "SOErr");
moni.show();
}
}