Merge branch 'main' into platformio

This commit is contained in:
Paul Vakhrushev
2021-03-01 22:36:33 +00:00
committed by GitHub
24 changed files with 685 additions and 508 deletions

Binary file not shown.

Binary file not shown.

View File

@@ -1,3 +1,12 @@
Отправляем на адрес x.x.x.255, первые 3 октета - адрес сети, к которой подключен смартфон Отправляем на адрес x.x.x.255, первые 3 октета - адрес сети, к которой подключен смартфон
UDP пакет вида <ключ>,<канал>,<тип>,<дата1>,<дата2>... разделитель - запятая
Ключ зашит в прошивке и задаётся в приложении (защита от управления "чужаком") Порт UDP формируется из имени сети:
GLkey = "ключ"
portNum = 17; // uint16_t (или % 65536)
for (byte i = 0; i < длина ключа; i++) portNum *= GLkey[i];
portNum %= 15000;
portNum += 50000;
portNum += номер группы
Таким образом порт лежит в диапазоне 50 001... 65 010
UDP пакет вида <GL>,<тип>,<дата1>,<дата2>... разделитель - запятая

View File

@@ -0,0 +1,80 @@
void sendUDP(char *data) {
Udp.beginPacket(deviceIP, portNum + cfg.group);
Udp.write(data);
Udp.endPacket();
}
void sendUDP(byte cmd, int data1 = 0, int data2 = 0, int data3 = 0) {
char reply[20] = "";
mString packet(reply, sizeof(reply));
packet = packet + "GL," + cmd + ',' + data1 + ',' + data2 + ',' + data3;
sendUDP(reply);
//DEBUG("Sending: ");
//DEBUGLN(cmd);
}
void restartUDP() {
Udp.stop();
Udp.begin(portNum + cfg.group);
deviceIP = WiFi.localIP();
deviceIP[3] = 255;
DEBUG("UDP port: ");
DEBUGLN(portNum + cfg.group);
}
void blink16(CRGB color) {
FOR_i(0, 3) {
fill_solid(leds, 16, color);
FastLED.show();
delay(300);
FastLED.clear();
FastLED.show();
delay(300);
}
}
const uint8_t font5x7[][5] = {
{0x3e, 0x51, 0x49, 0x45, 0x3e}, // 0 0x30 48
{0x00, 0x42, 0x7f, 0x40, 0x00}, // 1 0x31 49
{0x42, 0x61, 0x51, 0x49, 0x46}, // 2 0x32 50
{0x21, 0x41, 0x45, 0x4b, 0x31}, // 3 0x33 51
{0x18, 0x14, 0x12, 0x7f, 0x10}, // 4 0x34 52
{0x27, 0x45, 0x45, 0x45, 0x39}, // 5 0x35 53
{0x3c, 0x4a, 0x49, 0x49, 0x30}, // 6 0x36 54
{0x01, 0x71, 0x09, 0x05, 0x03}, // 7 0x37 55
{0x36, 0x49, 0x49, 0x49, 0x36}, // 8 0x38 56
{0x06, 0x49, 0x49, 0x29, 0x1e}, // 9 0x39 57
{0x00, 0x08, 0x08, 0x08, 0x00}, // 10 -
{0x00, 0x00, 0x00, 0x00, 0x00}, // 11 empty
};
void drawDigit(byte digit, int X, int Y, CRGB color) {
FOR_i(0, 5) {
FOR_j(0, 7) {
if (font5x7[digit][i] & (1 << 6 - j)) setPix(i + X, j + Y, color);
}
}
}
void drawDots(int X, int Y, CRGB color) {
setPix(X, Y + 2, color);
setPix(X, Y + 4, color);
}
void drawClock(byte Y, byte speed, CRGB color) {
if (cfg.deviceType == 1 || cfg.width < 16) return; // лента или мелкая матрица - на выход
byte h1, h2, m1, m2;
if (gotNTP || gotTime) {
h1 = now.hour / 10;
if (h1 == 0) h1 = 11;
h2 = now.hour % 10;
m1 = now.min / 10;
m2 = now.min % 10;
} else {
h1 = h2 = m1 = m2 = 10;
}
int pos = cfg.width - (now.weekMs / (speed * 2)) % (cfg.width + 26);
drawDigit(h1, pos, Y, color);
drawDigit(h2, pos + 6, Y, color);
if (now.getMs() < 500) drawDots(pos + 12, Y, color);
drawDigit(m1, pos + 14, Y, color);
drawDigit(m2, pos + 20, Y, color);
}

View File

@@ -1,4 +1,22 @@
/* /*
Версия 0.19b
Минимальная версия приложения 1.17!!!
Почищен мусор, оптимизация, повышена стабильность и производительность
Мигает теперь 16 светиков
Снова переделана сетевая политика, упрощён и сильно ускорен парсинг
Изменены пределы по светодиодам, что сильно увеличило производительность
Выключенная (программно) лампа не принимает сервисные команды кроме команды включиться
Добавлены часы, в том числе в рассвет
Slave работает со светомузыкой сам, если не получает данные с мастера
Версия 0.18b
Уменьшена чувствительность хлопков
Увеличена плавность светомузыки
Переделана сетевая политика
Микрофон и датчик света опрашивает только мастер и отсылает данные слейвам своей группы
4 клика - включить первый режим
Отправка точного времени на лампу в режиме АР для работы рассвета и синхронизации эффектов
Версия 0.17b Версия 0.17b
Автосмена отключается 30 сек во время настройки режимов Автосмена отключается 30 сек во время настройки режимов
Убрана кнопка upload в режимах Убрана кнопка upload в режимах
@@ -38,12 +56,9 @@
TODO: TODO:
плавная смена режимов плавная смена режимов
4 клика вкл выкл смену?
Mqtt? Mqtt?
Базовый пак Базовый пак
Предложения Серёги крутского
Эффект погода https://it4it.club/topic/40-esp8266-i-parsing-pogodyi-s-openweathermap/ Эффект погода https://it4it.club/topic/40-esp8266-i-parsing-pogodyi-s-openweathermap/
Эффект часы
*/ */
// ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! // ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ! ВНИМАНИЕ!
@@ -69,7 +84,7 @@
// ------------ Лента ------------- // ------------ Лента -------------
#define STRIP_PIN 2 // пин ленты GPIO2 (D4 на wemos/node) #define STRIP_PIN 2 // пин ленты GPIO2 (D4 на wemos/node)
#define MAX_LEDS 600 // макс. светодиодов #define MAX_LEDS 300 // макс. светодиодов
#define STRIP_CHIP WS2812 // чип ленты #define STRIP_CHIP WS2812 // чип ленты
#define STRIP_COLOR GRB // порядок цветов в ленте #define STRIP_COLOR GRB // порядок цветов в ленте
#define STRIP_VOLT 5 // напряжение ленты, V #define STRIP_VOLT 5 // напряжение ленты, V
@@ -86,15 +101,15 @@ const char AP_NameChar[] = "GyverLamp2";
const char WiFiPassword[] = "12345678"; const char WiFiPassword[] = "12345678";
// ------------ Прочее ------------- // ------------ Прочее -------------
#define GL_VERSION 017 // код версии прошивки #define GL_VERSION 19 // код версии прошивки
#define EE_TOUT 30000 // таймаут сохранения епром после изменения, мс #define EE_TOUT 30000 // таймаут сохранения епром после изменения, мс
//#define DEBUG_SERIAL_LAMP // закомментируй чтобы выключить отладку (скорость 115200) #define DEBUG_SERIAL_LAMP // закомментируй чтобы выключить отладку (скорость 115200)
#define EE_KEY 55 // ключ сброса WiFi (измени для сброса всех настроек) #define EE_KEY 55 // ключ сброса WiFi (измени для сброса всех настроек)
#define NTP_UPD_PRD 5 // период обновления времени с NTP сервера, минут #define NTP_UPD_PRD 5 // период обновления времени с NTP сервера, минут
//#define SKIP_WIFI // пропустить подключение к вафле (для отладки) //#define SKIP_WIFI // пропустить подключение к вафле (для отладки)
// ------------ БИЛДЕР ------------- // ------------ БИЛДЕР -------------
//#define MAX_LEDS 1200 //#define MAX_LEDS 900
// esp01 // esp01
//#define BTN_PIN 0 //#define BTN_PIN 0
@@ -105,6 +120,7 @@ const char WiFiPassword[] = "12345678";
//#define STRIP_PIN 5 // GPIO5 на gl module (D1 на wemos/node) //#define STRIP_PIN 5 // GPIO5 на gl module (D1 на wemos/node)
// ---------- БИБЛИОТЕКИ ----------- // ---------- БИБЛИОТЕКИ -----------
#define FASTLED_ALLOW_INTERRUPTS 0
#include "data.h" // данные #include "data.h" // данные
#include "Time.h" // часы #include "Time.h" // часы
#include "TimeRandom.h" // случайные числа по времени #include "TimeRandom.h" // случайные числа по времени
@@ -115,7 +131,6 @@ const char WiFiPassword[] = "12345678";
#include "timerMillis.h" // таймер миллис #include "timerMillis.h" // таймер миллис
#include "VolAnalyzer.h" // анализатор громкости #include "VolAnalyzer.h" // анализатор громкости
#include "FFT_C.h" // фурье #include "FFT_C.h" // фурье
#define FASTLED_ALLOW_INTERRUPTS 0
#include <FastLED.h> // лента #include <FastLED.h> // лента
#include <ESP8266WiFi.h> // базовая либа есп #include <ESP8266WiFi.h> // базовая либа есп
#include <WiFiUdp.h> // общение по UDP #include <WiFiUdp.h> // общение по UDP
@@ -132,31 +147,35 @@ Palette pal;
WiFiServer server(80); WiFiServer server(80);
WiFiUDP Udp; WiFiUDP Udp;
WiFiUDP ntpUDP; WiFiUDP ntpUDP;
IPAddress deviceIP;
NTPClient ntp(ntpUDP); NTPClient ntp(ntpUDP);
CRGB leds[MAX_LEDS]; CRGB leds[MAX_LEDS];
Time now; Time now;
Button btn(BTN_PIN); Button btn(BTN_PIN);
timerMillis EEtmr(EE_TOUT), turnoffTmr, connTmr(120000ul), dawnTmr, holdPresTmr(30000ul), blinkTmr(300); timerMillis EEtmr(EE_TOUT), turnoffTmr, connTmr(120000ul), dawnTmr, holdPresTmr(30000ul), blinkTmr(300);
timerMillis effTmr(30, true);
TimeRandom trnd; TimeRandom trnd;
VolAnalyzer vol(A0), low, high; VolAnalyzer vol(A0), low, high;
FastFilter phot; FastFilter phot;
Clap clap; Clap clap;
uint16_t portNum;
uint32_t udpTmr = 0, gotADCtmr = 0;
byte btnClicks = 0, brTicks = 0; byte btnClicks = 0, brTicks = 0;
unsigned char matrixValue[11][16]; unsigned char matrixValue[11][16];
bool gotNTP = false, gotTime = false; bool gotNTP = false, gotTime = false;
bool loading = true; bool loading = true;
void blink8(CRGB color); int udpLength = 0;
byte udpScale = 0, udpBright = 0;
// ------------------- SETUP -------------------- // ------------------- SETUP --------------------
void setup() { void setup() {
misc();
delay(2000); // ждём старта есп delay(2000); // ждём старта есп
memset(matrixValue, 0, sizeof(matrixValue));
#ifdef DEBUG_SERIAL_LAMP #ifdef DEBUG_SERIAL_LAMP
Serial.begin(115200); Serial.begin(115200);
DEBUGLN(); DEBUGLN();
#endif #endif
EEPROM.begin(1000); // старт епром
startStrip(); // старт ленты startStrip(); // старт ленты
btn.setLevel(digitalRead(BTN_PIN)); // смотрим что за кнопка btn.setLevel(digitalRead(BTN_PIN)); // смотрим что за кнопка
EE_startup(); // читаем епром EE_startup(); // читаем епром
@@ -174,6 +193,7 @@ void setup() {
void loop() { void loop() {
timeTicker(); // обновляем время timeTicker(); // обновляем время
yield();
#ifndef SKIP_WIFI #ifndef SKIP_WIFI
tryReconnect(); // пробуем переподключиться если WiFi упал tryReconnect(); // пробуем переподключиться если WiFi упал
yield(); yield();
@@ -186,4 +206,5 @@ void loop() {
yield(); yield();
button(); // проверяем кнопку button(); // проверяем кнопку
checkAnalog(); // чтение звука и датчика checkAnalog(); // чтение звука и датчика
yield();
} }

View File

@@ -1,22 +1,22 @@
/** /**
* The MIT License (MIT) The MIT License (MIT)
* Copyright (c) 2015 by Fabrice Weinberg Copyright (c) 2015 by Fabrice Weinberg
*
* Permission is hereby granted, free of charge, to any person obtaining a copy Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions: furnished to do so, subject to the following conditions:
* The above copyright notice and this permission notice shall be included in all The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. copies or substantial portions of the Software.
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE. SOFTWARE.
*/ */
#include "NTPClient-Gyver.h" #include "NTPClient-Gyver.h"

View File

@@ -36,34 +36,34 @@ class NTPClient {
NTPClient(UDP& udp, const char* poolServerName, long timeOffset, unsigned long updateInterval); NTPClient(UDP& udp, const char* poolServerName, long timeOffset, unsigned long updateInterval);
/** /**
* Set time server name Set time server name
*
* @param poolServerName @param poolServerName
*/ */
void setPoolServerName(const char* poolServerName); void setPoolServerName(const char* poolServerName);
/** /**
* Starts the underlying UDP client with the default local port Starts the underlying UDP client with the default local port
*/ */
void begin(); void begin();
/** /**
* Starts the underlying UDP client with the specified local port Starts the underlying UDP client with the specified local port
*/ */
void begin(int port); void begin(int port);
/** /**
* This should be called in the main loop of your application. By default an update from the NTP Server is only This should be called in the main loop of your application. By default an update from the NTP Server is only
* made every 60 seconds. This can be configured in the NTPClient constructor. made every 60 seconds. This can be configured in the NTPClient constructor.
*
* @return true on success, false on failure @return true on success, false on failure
*/ */
bool update(); bool update();
/** /**
* This will force the update from the NTP Server. This will force the update from the NTP Server.
*
* @return true on success, false on failure @return true on success, false on failure
*/ */
bool forceUpdate(); bool forceUpdate();
@@ -75,28 +75,28 @@ class NTPClient {
int getMillisLastUpd() const; int getMillisLastUpd() const;
/** /**
* Changes the time offset. Useful for changing timezones dynamically Changes the time offset. Useful for changing timezones dynamically
*/ */
void setTimeOffset(int timeOffset); void setTimeOffset(int timeOffset);
/** /**
* Set the update interval to another frequency. E.g. useful when the Set the update interval to another frequency. E.g. useful when the
* timeOffset should not be set in the constructor timeOffset should not be set in the constructor
*/ */
void setUpdateInterval(unsigned long updateInterval); void setUpdateInterval(unsigned long updateInterval);
/** /**
* @return time formatted like `hh:mm:ss` @return time formatted like `hh:mm:ss`
*/ */
String getFormattedTime() const; String getFormattedTime() const;
/** /**
* @return time in seconds since Jan. 1, 1970 @return time in seconds since Jan. 1, 1970
*/ */
unsigned long getEpochTime() const; unsigned long getEpochTime() const;
/** /**
* Stops the underlying UDP client Stops the underlying UDP client
*/ */
void end(); void end();
}; };

View File

@@ -9,7 +9,7 @@ class Time {
uint32_t weekS = 0; uint32_t weekS = 0;
int getMs() { int getMs() {
return (millis() - tmr); return (tmr - millis());
} }
void setMs(int ms) { void setMs(int ms) {
tmr = millis() + ms; tmr = millis() + ms;

View File

@@ -1,6 +1,12 @@
#if (USE_ADC == 1) #if (USE_ADC == 1)
void setupADC() { void setupADC() {
clap.setTimeout(500); clap.setTimeout(500);
clap.setTrsh(250);
vol.setDt(700);
vol.setPeriod(5);
vol.setWindow(map(MAX_LEDS, 300, 1200, 20, 1));
low.setDt(0); low.setDt(0);
low.setPeriod(0); low.setPeriod(0);
low.setWindow(0); low.setWindow(0);
@@ -8,9 +14,9 @@ void setupADC() {
high.setPeriod(0); high.setPeriod(0);
high.setWindow(0); high.setWindow(0);
vol.setVolK(20); vol.setVolK(26);
low.setVolK(20); low.setVolK(26);
high.setVolK(20); high.setVolK(26);
vol.setTrsh(50); vol.setTrsh(50);
low.setTrsh(50); low.setTrsh(50);
@@ -33,7 +39,7 @@ void setupADC() {
void checkAnalog() { void checkAnalog() {
//if (cfg.state) { if (cfg.role || millis() - gotADCtmr >= 2000) { // только мастер или слейв по таймауту опрашивает АЦП!
switch (cfg.adcMode) { switch (cfg.adcMode) {
case GL_ADC_NONE: break; case GL_ADC_NONE: break;
case GL_ADC_BRI: checkPhot(); break; case GL_ADC_BRI: checkPhot(); break;
@@ -52,7 +58,7 @@ void checkAnalog() {
} }
break; break;
} }
//} }
} }
void checkMusic() { void checkMusic() {
@@ -61,10 +67,11 @@ void checkMusic() {
clap.tick(vol.getRawMax()); clap.tick(vol.getRawMax());
if (clap.hasClaps(2)) controlHandler(!cfg.state); if (clap.hasClaps(2)) controlHandler(!cfg.state);
#endif #endif
yield();
if (CUR_PRES.advMode == GL_ADV_LOW || CUR_PRES.advMode == GL_ADV_HIGH) { // частоты if (CUR_PRES.advMode == GL_ADV_LOW || CUR_PRES.advMode == GL_ADV_HIGH) { // частоты
int raw[FFT_SIZE], spectr[FFT_SIZE]; int raw[FFT_SIZE], spectr[FFT_SIZE];
for (int i = 0; i < FFT_SIZE; i++) raw[i] = analogRead(A0); for (int i = 0; i < FFT_SIZE; i++) raw[i] = analogRead(A0);
yield();
FFT(raw, spectr); FFT(raw, spectr);
int low_raw = 0; int low_raw = 0;
int high_raw = 0; int high_raw = 0;

View File

@@ -27,11 +27,17 @@ void button() {
changePreset(-1); changePreset(-1);
sendToSlaves(1, cfg.curPreset); sendToSlaves(1, cfg.curPreset);
break; break;
case 4:
setPreset(0);
sendToSlaves(1, cfg.curPreset);
break;
case 5: case 5:
cfg.role = 0; cfg.role = 0;
blink16(CRGB::DarkSlateBlue);
break; break;
case 6: case 6:
cfg.role = 1; cfg.role = 1;
blink16(CRGB::Maroon);
break; break;
} }
EE_updateCfg(); EE_updateCfg();

View File

@@ -41,12 +41,12 @@ int mapFF(byte x, byte min, byte max) {
const char OTAhost[] = "http://ota.alexgyver.ru/"; const char OTAhost[] = "http://ota.alexgyver.ru/";
const char *OTAfile[] = { const char *OTAfile[] = {
"GL2_latest.bin", "GL2_latest.bin",
"com_600.bin", "com_300.bin",
"com_1200.bin", "com_900.bin",
"esp1_600.bin", "esp1_300.bin",
"esp1_1200.bin", "esp1_900.bin",
"module_600.bin", "module_300.bin",
"module_1200.bin", "module_900.bin",
}; };
const char NTPserver[] = "pool.ntp.org"; const char NTPserver[] = "pool.ntp.org";
@@ -56,6 +56,7 @@ const char NTPserver[] = "pool.ntp.org";
//"ntp2.stratum2.ru" //"ntp2.stratum2.ru"
//"ntp.msk-ix.ru" //"ntp.msk-ix.ru"
#define PAL_SIZE 49
struct Palette { struct Palette {
byte size = 1; byte size = 1;
byte strip[16 * 3]; byte strip[16 * 3];
@@ -120,6 +121,7 @@ struct Preset {
byte rnd = 0; // случайный (0/1) byte rnd = 0; // случайный (0/1)
}; };
#define DAWN_SIZE 23
struct Dawn { struct Dawn {
byte state[7] = {0, 0, 0, 0, 0, 0, 0}; // (1/0) byte state[7] = {0, 0, 0, 0, 0, 0, 0}; // (1/0)
byte hour[7] = {0, 0, 0, 0, 0, 0, 0}; // (0.. 59) byte hour[7] = {0, 0, 0, 0, 0, 0, 0}; // (0.. 59)
@@ -127,3 +129,9 @@ struct Dawn {
byte bright = 100; // (0.. 255) byte bright = 100; // (0.. 255)
byte time = 1; // (5,10,15,20..) byte time = 1; // (5,10,15,20..)
}; };
/*
- Каждые 5 минут лампа AP отправляет время (день час минута) на Local лампы всех ролей в сети с ней (GL,6,день,час,мин)
- Если включен АЦП, Мастер отправляет своей группе данные с него на каждой итерации отрисовки эффектов (GL,1,длина,масштаб,яркость)
- Установка времени с мобилы - получают все роли АР и Local (не получившие ntp)
*/

View File

@@ -5,6 +5,8 @@ bool EEpalFlag = false;
void EE_startup() { void EE_startup() {
// старт епром // старт епром
EEPROM.begin(1000); // старт епром
delay(100);
if (EEPROM.read(0) != EE_KEY) { if (EEPROM.read(0) != EE_KEY) {
EEPROM.write(0, EE_KEY); EEPROM.write(0, EE_KEY);
EEPROM.put(1, cfg); EEPROM.put(1, cfg);
@@ -12,7 +14,7 @@ void EE_startup() {
EEPROM.put(sizeof(cfg) + sizeof(dawn) + 1, pal); EEPROM.put(sizeof(cfg) + sizeof(dawn) + 1, pal);
EEPROM.put(sizeof(cfg) + sizeof(dawn) + sizeof(pal) + 1, preset); EEPROM.put(sizeof(cfg) + sizeof(dawn) + sizeof(pal) + 1, preset);
EEPROM.commit(); EEPROM.commit();
blink8(CRGB::Magenta); blink16(CRGB::Magenta);
DEBUGLN("First start"); DEBUGLN("First start");
} }
EEPROM.get(1, cfg); EEPROM.get(1, cfg);

View File

@@ -1,12 +1,11 @@
void effectsRoutine() { void effectsRoutine() {
static timerMillis effTmr(30, true);
static byte prevEff = 255; static byte prevEff = 255;
if (!effTmr.isReady()) return;
if (dawnTmr.running()) { if (dawnTmr.running()) {
if (effTmr.isReady()) {
fill_solid(leds, MAX_LEDS, ColorFromPalette(HeatColors_p, dawnTmr.getLength8(), scaleFF(dawnTmr.getLength8(), dawn.bright), LINEARBLEND)); fill_solid(leds, MAX_LEDS, ColorFromPalette(HeatColors_p, dawnTmr.getLength8(), scaleFF(dawnTmr.getLength8(), dawn.bright), LINEARBLEND));
drawClock(cfg.length / 2 - 4, 150, 0);
FastLED.show(); FastLED.show();
}
if (dawnTmr.isReady()) { if (dawnTmr.isReady()) {
dawnTmr.stop(); dawnTmr.stop();
FastLED.clear(); FastLED.clear();
@@ -15,12 +14,24 @@ void effectsRoutine() {
return; return;
} }
if (cfg.state && effTmr.isReady()) { if (!cfg.state) return;
int thisLength = getLength(); int thisLength = getLength();
byte thisScale = getScale(); byte thisScale = getScale();
int thisWidth = (cfg.deviceType > 1) ? cfg.width : 1;
byte thisBright = getBright(); byte thisBright = getBright();
if (cfg.adcMode > 1) { // музыка или яркость
if (cfg.role) { // мастер отправляет
static timerMillis adcSend(120, true);
if (adcSend.isReady() && millis() - udpTmr >= 1000) sendUDP(7, thisLength, thisScale, thisBright);
} else { // слейв получает
if (millis() - gotADCtmr < 2000) { // есть сигнал с мастера
thisLength = udpLength;
thisScale = udpScale;
thisBright = udpBright;
}
}
}
if (turnoffTmr.running()) thisBright = scaleFF(thisBright, 255 - turnoffTmr.getLength8()); if (turnoffTmr.running()) thisBright = scaleFF(thisBright, 255 - turnoffTmr.getLength8());
else if (blinkTmr.runningStop()) thisBright = scaleFF(thisBright, blinkTmr.getLength8()); else if (blinkTmr.runningStop()) thisBright = scaleFF(thisBright, blinkTmr.getLength8());
if (turnoffTmr.isReady()) { if (turnoffTmr.isReady()) {
@@ -30,11 +41,12 @@ void effectsRoutine() {
} }
FastLED.setBrightness(thisBright); FastLED.setBrightness(thisBright);
if (prevEff != CUR_PRES.effect) { if (prevEff != CUR_PRES.effect) { // смена эффекта
FastLED.clear(); FastLED.clear();
prevEff = CUR_PRES.effect; prevEff = CUR_PRES.effect;
loading = true; loading = true;
} }
// =================================================== ЭФФЕКТЫ =================================================== // =================================================== ЭФФЕКТЫ ===================================================
switch (CUR_PRES.effect) { switch (CUR_PRES.effect) {
case 1: // =================================== ПЕРЛИН =================================== case 1: // =================================== ПЕРЛИН ===================================
@@ -62,7 +74,7 @@ void effectsRoutine() {
case 2: // ==================================== ЦВЕТ ==================================== case 2: // ==================================== ЦВЕТ ====================================
{ {
fill_solid(leds, cfg.length * thisWidth, CHSV(CUR_PRES.color, thisScale, 30)); fill_solid(leds, cfg.length * cfg.width, CHSV(CUR_PRES.color, thisScale, 30));
CRGB thisColor = CHSV(CUR_PRES.color, thisScale, thisBright); CRGB thisColor = CHSV(CUR_PRES.color, thisScale, thisBright);
if (CUR_PRES.fromCenter) { if (CUR_PRES.fromCenter) {
fillStrip(cfg.length / 2, cfg.length / 2 + thisLength / 2, thisColor); fillStrip(cfg.length / 2, cfg.length / 2 + thisLength / 2, thisColor);
@@ -76,7 +88,7 @@ void effectsRoutine() {
case 3: // ================================= СМЕНА ЦВЕТА ================================= case 3: // ================================= СМЕНА ЦВЕТА =================================
{ {
CRGB thisColor = ColorFromPalette(paletteArr[CUR_PRES.palette - 1], scalePal((now.weekMs >> 5) * CUR_PRES.speed / 255), 10, LINEARBLEND); CRGB thisColor = ColorFromPalette(paletteArr[CUR_PRES.palette - 1], scalePal((now.weekMs >> 5) * CUR_PRES.speed / 255), 10, LINEARBLEND);
fill_solid(leds, cfg.length * thisWidth, thisColor); fill_solid(leds, cfg.length * cfg.width, thisColor);
thisColor = ColorFromPalette(paletteArr[CUR_PRES.palette - 1], scalePal((now.weekMs >> 5) * CUR_PRES.speed / 255), thisBright, LINEARBLEND); thisColor = ColorFromPalette(paletteArr[CUR_PRES.palette - 1], scalePal((now.weekMs >> 5) * CUR_PRES.speed / 255), thisBright, LINEARBLEND);
if (CUR_PRES.fromCenter) { if (CUR_PRES.fromCenter) {
fillStrip(cfg.length / 2, cfg.length / 2 + thisLength / 2, thisColor); fillStrip(cfg.length / 2, cfg.length / 2 + thisLength / 2, thisColor);
@@ -202,20 +214,25 @@ void effectsRoutine() {
} }
break; break;
case 9: // ================================== ПОГОДА ================================== case 9: // =================================== ЧАСЫ ===================================
FastLED.clear();
drawClock(mapFF(CUR_PRES.scale, 0, cfg.length - 7), (255 - CUR_PRES.speed), CHSV(CUR_PRES.color, 255, 255));
break;
case 10: // ================================= ПОГОДА ==================================
break; break;
} }
if (CUR_PRES.advMode == GL_ADV_CLOCK && CUR_PRES.effect != 9) drawClock(mapFF(CUR_PRES.scale, 0, cfg.length - 7), 150, 0);
// выводим нажатия кнопки // выводим нажатия кнопки
if (btnClicks > 0) fill_solid(leds, btnClicks, CRGB::White); if (btnClicks > 0) fill_solid(leds, btnClicks, CRGB::White);
if (brTicks > 0) fill_solid(leds, brTicks, CRGB::Cyan); if (brTicks > 0) fill_solid(leds, brTicks, CRGB::Cyan);
yield();
FastLED.show(); FastLED.show();
} }
}
// ==================================================================================================================== // ====================================================================================================================
bool musicMode() { bool musicMode() {
return ((cfg.adcMode == GL_ADC_MIC || cfg.adcMode == GL_ADC_BOTH) && (CUR_PRES.advMode > 1 && CUR_PRES.advMode <= 4)); return ((cfg.adcMode == GL_ADC_MIC || cfg.adcMode == GL_ADC_BOTH) && (CUR_PRES.advMode > 1 && CUR_PRES.advMode <= 4));
} }
@@ -273,17 +290,6 @@ void updPal() {
if (pal.size < 16) paletteArr[0][pal.size] = paletteArr[0][0]; if (pal.size < 16) paletteArr[0][pal.size] = paletteArr[0][0];
} }
void blink8(CRGB color) {
FOR_i(0, 3) {
fill_solid(leds, 8, color);
FastLED.show();
delay(300);
FastLED.clear();
FastLED.show();
delay(300);
}
}
byte scalePal(byte val) { byte scalePal(byte val) {
if (CUR_PRES.palette == 1) val = val * pal.size / 16; if (CUR_PRES.palette == 1) val = val * pal.size / 16;
return val; return val;

View File

@@ -43,68 +43,67 @@ char* mFtoa(double value, int8_t decimals, char *buffer) {
class mString { class mString {
public: public:
int size = 0;
char* buf; char* buf;
// system*this = buf; int size = 0;
uint16_t length() { uint16_t length() {
return strlen(buf); return strlen(buf);
} }
void clear() { void clear() {
buf[0] = 0; buf[0] = NULL;
} }
// constructor // constructor
mString(char* buffer, int newSize) { mString(char* buffer, int newSize) {
//*this = buf;
buf = buffer; buf = buffer;
size = newSize; size = newSize;
} }
/*mString (const char c) { /*mString (const char c) {
init(); //init();
add(c); add(c);
} }
mString (const char* data) { mString (const char* data) {
init(); //init();
add(data); add(data);
} }
mString (const __FlashStringHelper *data) { mString (const __FlashStringHelper *data) {
init(); //init();
add(data); add(data);
} }
mString (uint32_t value) { mString (uint32_t value) {
init(); //init();
add(value); add(value);
} }
mString (int32_t value) { mString (int32_t value) {
init(); //init();
add(value); add(value);
} }
mString (uint16_t value) { mString (uint16_t value) {
init(); //init();
add(value); add(value);
} }
mString (int16_t value) { mString (int16_t value) {
init(); //init();
add(value); add(value);
} }
mString (uint8_t value) { mString (uint8_t value) {
init(); //init();
add(value); add(value);
} }
mString (int8_t value) { mString (int8_t value) {
init(); //init();
add(value); add(value);
} }
mString (double value, byte dec = 2) { mString (double value, byte dec = 2) {
init(); //init();
add(value, dec); add(value, dec);
}*/ }*/
// add // add
mString& add(const char c) { mString& add(const char c) {
byte len = length(); byte len = length();
if (len + 1 >= size) return *this;
buf[len++] = c; buf[len++] = c;
buf[len++] = 0; buf[len++] = NULL;
return *this; return *this;
} }
mString& add(const char* data) { mString& add(const char* data) {
@@ -112,11 +111,13 @@ class mString {
do { do {
buf[len] = *(data++); buf[len] = *(data++);
} while (buf[len++] != 0);*/ } while (buf[len++] != 0);*/
if (length() + strlen(data) >= size) return *this;
strcpy(buf + length(), data); strcpy(buf + length(), data);
return *this; return *this;
} }
mString& add(const __FlashStringHelper *data) { mString& add(const __FlashStringHelper *data) {
PGM_P p = reinterpret_cast<PGM_P>(data); PGM_P p = reinterpret_cast<PGM_P>(data);
if (length() + strlen_P(p) >= size) return *this;
strcpy_P(buf + length(), p); strcpy_P(buf + length(), p);
return *this; return *this;
/*do { /*do {
@@ -125,10 +126,9 @@ class mString {
*/ */
} }
mString& add(uint32_t value) { mString& add(uint32_t value) {
//char buf[11]; char vBuf[11];
//return add(mUtoa(value, buf)); utoa(value, vBuf, DEC);
utoa(value, buf + length(), DEC); return add(vBuf);
return *this;
} }
mString& add(uint16_t value) { mString& add(uint16_t value) {
return add((uint32_t)value); return add((uint32_t)value);
@@ -137,10 +137,9 @@ class mString {
return add((uint32_t)value); return add((uint32_t)value);
} }
mString& add(int32_t value) { mString& add(int32_t value) {
//char buf[11]; char vBuf[11];
//return add(mLtoa(value, buf)); ltoa(value, vBuf, DEC);
ltoa(value, buf + length(), DEC); return add(vBuf);
return *this;
} }
mString& add(int16_t value) { mString& add(int16_t value) {
return add((int32_t)value); return add((int32_t)value);
@@ -149,11 +148,13 @@ class mString {
return add((int32_t)value); return add((int32_t)value);
} }
mString& add(double value, int8_t dec = 2) { mString& add(double value, int8_t dec = 2) {
char buf[20]; char vBuf[20];
return add(mFtoa(value, dec, buf)); mFtoa(value, dec, vBuf);
//dtostrf(value, dec, DEC, buf+length()); return add(vBuf);
//return *this;
} }
/*mString& add(mString data) {
return add(data.buf);
}*/
// add += // add +=
mString& operator += (const char c) { mString& operator += (const char c) {
@@ -186,6 +187,44 @@ class mString {
mString& operator += (double value) { mString& operator += (double value) {
return add(value); return add(value);
} }
/*mString& operator += (mString data) {
return add(data);
}*/
// +
mString operator + (const char c) {
return mString(*this) += c;
}
mString operator + (const char* data) {
return mString(*this) += data;
}
mString operator + (const __FlashStringHelper *data) {
return mString(*this) += data;
}
mString operator + (uint32_t value) {
return mString(*this) += value;
}
mString operator + (int32_t value) {
return mString(*this) += value;
}
mString operator + (uint16_t value) {
return mString(*this) += value;
}
mString operator + (int16_t value) {
return mString(*this) += value;
}
mString operator + (uint8_t value) {
return mString(*this) += value;
}
mString operator + (int8_t value) {
return mString(*this) += value;
}
mString operator + (double value) {
return mString(*this) += value;
}
/*mString operator + (mString data) {
return mString(*this) += data;
}*/
// assign // assign
mString& operator = (const char c) { mString& operator = (const char c) {
@@ -228,6 +267,10 @@ class mString {
clear(); clear();
return add(value); return add(value);
} }
/*mString& operator = (mString data) {
clear();
return add(data);
}*/
// compare // compare
bool operator == (const char c) { bool operator == (const char c) {
@@ -248,15 +291,17 @@ class mString {
char valBuf[20]; char valBuf[20];
return !strcmp(buf, mFtoa(value, 2, valBuf)); return !strcmp(buf, mFtoa(value, 2, valBuf));
} }
/*bool operator == (mString data) {
return (buf == data.buf);
}*/
// convert & parse
char operator [] (uint16_t index) const { char operator [] (uint16_t index) const {
return (index < size ? buf[index] : 0); return (index < size ? buf[index] : 0);
} }
char& operator [] (uint16_t index) { char& operator [] (uint16_t index) {
return buf[index]; return buf[index];
} }
// convert & parse
uint32_t toInt() { uint32_t toInt() {
return atoi(buf); return atoi(buf);
} }

View File

@@ -1,26 +1,41 @@
void parsing() { void parsing() {
if (Udp.parsePacket()) { if (Udp.parsePacket()) {
static uint32_t tmr = 0;
static char buf[UDP_TX_PACKET_MAX_SIZE + 1]; static char buf[UDP_TX_PACKET_MAX_SIZE + 1];
int n = Udp.read(buf, UDP_TX_PACKET_MAX_SIZE); int n = Udp.read(buf, UDP_TX_PACKET_MAX_SIZE);
if (millis() - tmr < 500) return; // принимаем посылки не чаще 2 раз в секунду
tmr = millis();
buf[n] = NULL; buf[n] = NULL;
DEBUGLN(buf); // пакет вида <ключ>,<канал>,<тип>,<дата1>,<дата2>...
byte keyLen = strchr(buf, ',') - buf; // indexof
if (strncmp(buf, GL_KEY, keyLen)) return; // не наш ключ
byte data[MAX_PRESETS * PRES_SIZE + 5]; // ПРЕ-ПАРСИНГ (для данных АЦП)
memset(data, 0, MAX_PRESETS * PRES_SIZE + 5); if (buf[0] != 'G' || buf[1] != 'L' || buf[2] != ',') return; // защита от не наших данных
if (buf[3] == '7') { // АЦП GL,7,
if (!cfg.role) { // принимаем данные ацп если слейв
int data[3];
mString ints(buf + 5, 20);
ints.parseInts(data, 3);
udpLength = data[0];
udpScale = data[1];
udpBright = data[2];
effTmr.force(); // форсируем отрисовку эффекта
gotADCtmr = millis();
}
return; // выходим
}
if (millis() - udpTmr < 500) return; // принимаем остальные посылки не чаще 2 раз в секунду
udpTmr = millis();
DEBUGLN(buf); // пакет вида <GL>,<тип>,<дата1>,<дата2>...
// ПАРСИНГ
byte data[MAX_PRESETS * PRES_SIZE + 10];
memset(data, 0, sizeof(data));
int count = 0; int count = 0;
char *str, *p = buf + keyLen; // сдвиг до даты char *str, *p = buf;
char *ssid, *pass; char *ssid, *pass;
while ((str = strtok_r(p, ",", &p)) != NULL) { while ((str = strtok_r(p, ",", &p)) != NULL) {
uint32_t thisInt = atoi(str); uint32_t thisInt = atoi(str);
data[count++] = (byte)thisInt; data[count++] = (byte)thisInt; // парс байтов
// парс "тяжёлых" данных
if (data[1] == 0) { if (data[1] == 0) {
if (count == 4) ssid = str; if (count == 4) ssid = str;
if (count == 5) pass = str; if (count == 5) pass = str;
@@ -38,20 +53,12 @@ void parsing() {
if (count == 24) strcpy(cfg.mqttPass, str); if (count == 24) strcpy(cfg.mqttPass, str);
} }
} }
yield();
// широковещательный запрос времени для local устройств в сети AP лампы // тип 0 - control, 1 - config, 2 - effects, 3 - dawn, 4 - from master, 5 - palette, 6 - time
if (data[0] == 0 && cfg.WiFimode && !gotNTP) { switch (data[1]) {
now.day = data[1];
now.hour = data[2];
now.min = data[3];
now.sec = data[4];
now.setMs(0);
}
if (data[0] != cfg.group) return; // не наш адрес, выходим
switch (data[1]) { // тип 0 - control, 1 - config, 2 - effects, 3 - dawn, 4 - from master, 5 - palette
case 0: DEBUGLN("Control"); blinkTmr.restart(); case 0: DEBUGLN("Control"); blinkTmr.restart();
if (!cfg.state && data[2] != 1) return; // если лампа выключена и это не команда на включение - не обрабатываем
switch (data[2]) { switch (data[2]) {
case 0: controlHandler(0); break; // выкл case 0: controlHandler(0); break; // выкл
case 1: controlHandler(1); break; // вкл case 1: controlHandler(1); break; // вкл
@@ -62,7 +69,7 @@ void parsing() {
case 6: setPreset(data[3] - 1); break; // конкретный пресет data[3] case 6: setPreset(data[3] - 1); break; // конкретный пресет data[3]
case 7: cfg.WiFimode = data[3]; EE_updCfgRst(); break; // смена режима WiFi case 7: cfg.WiFimode = data[3]; EE_updCfgRst(); break; // смена режима WiFi
case 8: cfg.role = data[3]; break; // смена роли case 8: cfg.role = data[3]; break; // смена роли
case 9: cfg.group = data[3]; break; // смена группы case 9: cfg.group = data[3]; restartUDP(); break; // смена группы
case 10: // установка настроек WiFi case 10: // установка настроек WiFi
strcpy(cfg.ssid, ssid); strcpy(cfg.ssid, ssid);
strcpy(cfg.pass, pass); strcpy(cfg.pass, pass);
@@ -90,6 +97,7 @@ void parsing() {
} }
break; break;
} }
if (data[2] < 7) setTime(data[3], data[4], data[5], data[6]);
EE_updCfg(); EE_updCfg();
break; break;
@@ -97,6 +105,7 @@ void parsing() {
FOR_i(0, CFG_SIZE) { FOR_i(0, CFG_SIZE) {
*((byte*)&cfg + i) = data[i + 2]; // загоняем в структуру *((byte*)&cfg + i) = data[i + 2]; // загоняем в структуру
} }
setTime(data[CFG_SIZE + 10 + 2], data[CFG_SIZE + 10 + 3], data[CFG_SIZE + 10 + 4], data[CFG_SIZE + 10 + 5]);
if (cfg.deviceType == GL_TYPE_STRIP) { if (cfg.deviceType == GL_TYPE_STRIP) {
if (cfg.length > MAX_LEDS) cfg.length = MAX_LEDS; if (cfg.length > MAX_LEDS) cfg.length = MAX_LEDS;
cfg.width = 1; cfg.width = 1;
@@ -111,6 +120,7 @@ void parsing() {
break; break;
case 2: DEBUGLN("Preset"); case 2: DEBUGLN("Preset");
{
cfg.presetAmount = data[2]; // кол-во режимов cfg.presetAmount = data[2]; // кол-во режимов
FOR_j(0, cfg.presetAmount) { FOR_j(0, cfg.presetAmount) {
FOR_i(0, PRES_SIZE) { FOR_i(0, PRES_SIZE) {
@@ -118,17 +128,22 @@ void parsing() {
} }
} }
//if (!cfg.rotation) setPreset(data[cfg.presetAmount * PRES_SIZE + 3] - 1); //if (!cfg.rotation) setPreset(data[cfg.presetAmount * PRES_SIZE + 3] - 1);
setPreset(data[cfg.presetAmount * PRES_SIZE + 3] - 1); byte dataStart = cfg.presetAmount * PRES_SIZE + 3;
setPreset(data[dataStart] - 1);
setTime(data[dataStart + 1], data[dataStart + 2], data[dataStart + 3], data[dataStart + 4]);
EE_updatePreset(); EE_updatePreset();
//presetRotation(true); // форсировать смену режима //presetRotation(true); // форсировать смену режима
holdPresTmr.restart(); holdPresTmr.restart();
loading = true; loading = true;
}
break; break;
case 3: DEBUGLN("Dawn"); blinkTmr.restart(); case 3: DEBUGLN("Dawn"); blinkTmr.restart();
FOR_i(0, (2 + 3 * 7)) { FOR_i(0, DAWN_SIZE) {
*((byte*)&dawn + i) = data[i + 2]; // загоняем в структуру *((byte*)&dawn + i) = data[i + 2]; // загоняем в структуру
} }
setTime(data[DAWN_SIZE + 2], data[DAWN_SIZE + 3], data[DAWN_SIZE + 4], data[DAWN_SIZE + 5]);
EE_updateDawn(); EE_updateDawn();
break; break;
@@ -144,20 +159,23 @@ void parsing() {
break; break;
case 5: DEBUGLN("Palette"); blinkTmr.restart(); case 5: DEBUGLN("Palette"); blinkTmr.restart();
FOR_i(0, 1 + 16 * 3) { FOR_i(0, PAL_SIZE) {
*((byte*)&pal + i) = data[i + 2]; // загоняем в структуру *((byte*)&pal + i) = data[i + 2]; // загоняем в структуру
} }
setTime(data[PAL_SIZE + 2], data[PAL_SIZE + 3], data[PAL_SIZE + 4], data[PAL_SIZE + 5]);
updPal(); updPal();
EE_updatePal(); EE_updatePal();
break; break;
case 6: DEBUGLN("Time"); blinkTmr.restart(); case 6: DEBUGLN("Time from AP");
if (!cfg.WiFimode) { // если мы AP if (cfg.WiFimode && !gotNTP) { // время для local устройств в сети AP лампы (не получили время из интернета)
now.day = data[2]; now.day = data[2];
now.hour = data[3]; now.hour = data[3];
now.min = data[4]; now.min = data[4];
now.sec = 0;
now.setMs(0);
DEBUGLN("Got time from master");
} }
gotTime = true;
break; break;
} }
FastLED.clear(); // на всякий случай FastLED.clear(); // на всякий случай
@@ -166,27 +184,16 @@ void parsing() {
void sendToSlaves(byte data1, byte data2) { void sendToSlaves(byte data1, byte data2) {
if (cfg.role == GL_MASTER) { if (cfg.role == GL_MASTER) {
IPAddress ip = WiFi.localIP(); char reply[15];
ip[3] = 255;
char reply[20];
mString packet(reply, sizeof(reply)); mString packet(reply, sizeof(reply));
packet.clear(); packet.clear();
packet += GL_KEY; packet = packet + "GL,4," + data1 + ',' + data2;
packet += ',';
packet += cfg.group;
packet += ",4,";
packet += data1;
packet += ',';
packet += data2;
DEBUG("Sending to Slaves: "); DEBUG("Sending to Slaves: ");
DEBUGLN(reply); DEBUGLN(reply);
FOR_i(0, 3) { FOR_i(0, 3) {
Udp.beginPacket(ip, 8888); sendUDP(reply);
Udp.write(reply);
Udp.endPacket();
delay(10); delay(10);
} }
} }

View File

@@ -14,14 +14,14 @@ void presetRotation(bool force) {
} }
void changePreset(int dir) { void changePreset(int dir) {
if (!cfg.rotation) { // ручная смена //if (!cfg.rotation) { // ручная смена
cfg.curPreset += dir; cfg.curPreset += dir;
if (cfg.curPreset >= cfg.presetAmount) cfg.curPreset = 0; if (cfg.curPreset >= cfg.presetAmount) cfg.curPreset = 0;
if (cfg.curPreset < 0) cfg.curPreset = cfg.presetAmount - 1; if (cfg.curPreset < 0) cfg.curPreset = cfg.presetAmount - 1;
holdPresTmr.restart(); holdPresTmr.restart();
DEBUG("Preset changed to "); DEBUG("Preset changed to ");
DEBUGLN(cfg.curPreset); DEBUGLN(cfg.curPreset);
} //}
} }
void setPreset(byte pres) { void setPreset(byte pres) {
@@ -61,13 +61,14 @@ void fade(bool state) {
} }
void setPower(bool state) { void setPower(bool state) {
if (cfg.state != state) EE_updateCfg(); // на сохранение
cfg.state = state; cfg.state = state;
if (!state) { if (!state) {
delay(100); // чтобы пролететь мин. частоту обновления delay(100); // чтобы пролететь мин. частоту обновления
FastLED.clear(); FastLED.clear();
FastLED.show(); FastLED.show();
} }
sendToSlaves(0, cfg.state); if (millis() - udpTmr >= 1000) sendToSlaves(0, cfg.state); // пиздец костыль
DEBUGLN(state ? "Power on" : "Power off"); DEBUGLN(state ? "Power on" : "Power off");
} }

View File

@@ -86,15 +86,13 @@ void startWiFi() {
if (!cfg.WiFimode) setupAP(); // режим точки доступа if (!cfg.WiFimode) setupAP(); // режим точки доступа
else setupLocal(); // подключаемся к точке else setupLocal(); // подключаемся к точке
DEBUG("UDP port: "); restartUDP();
DEBUGLN(8888);
Udp.begin(8888);
FastLED.clear(); FastLED.clear();
FastLED.show(); FastLED.show();
} }
void setupAP() { void setupAP() {
blink8(CRGB::Yellow); blink16(CRGB::Yellow);
WiFi.disconnect(); WiFi.disconnect();
WiFi.mode(WIFI_AP); WiFi.mode(WIFI_AP);
delay(100); delay(100);
@@ -131,12 +129,12 @@ void setupLocal() {
leds[count] = CRGB::Yellow; leds[count] = CRGB::Yellow;
FastLED.show(); FastLED.show();
count += dir; count += dir;
if (count >= 7 || count <= 0) dir *= -1; if (count >= 15 || count <= 0) dir *= -1;
delay(50); delay(50);
} }
if (connect) { if (connect) {
connTmr.stop(); connTmr.stop();
blink8(CRGB::Green); blink16(CRGB::Green);
server.begin(); server.begin();
DEBUG("Connected! Local IP: "); DEBUG("Connected! Local IP: ");
DEBUGLN(WiFi.localIP()); DEBUGLN(WiFi.localIP());
@@ -144,18 +142,13 @@ void setupLocal() {
return; return;
} else { } else {
DEBUGLN("Failed!"); DEBUGLN("Failed!");
blink8(CRGB::Red); blink16(CRGB::Red);
failCount++; failCount++;
tmr = millis(); tmr = millis();
if (failCount >= 3) { if (failCount >= 3) {
connTmr.restart(); // попробуем позже connTmr.restart(); // попробуем позже
setupAP(); setupAP();
return; return;
/*DEBUGLN("Reboot to AP!");
cfg.WiFimode = 0;
EE_updCfg();
delay(100);
ESP.restart();*/
} }
} }
} }
@@ -166,11 +159,11 @@ void checkUpdate() {
if (cfg.update) { if (cfg.update) {
if (cfg.version != GL_VERSION) { if (cfg.version != GL_VERSION) {
cfg.version = GL_VERSION; cfg.version = GL_VERSION;
blink8(CRGB::Cyan); blink16(CRGB::Cyan);
DEBUG("Update to"); DEBUG("Update to");
DEBUGLN(GL_VERSION); DEBUGLN(GL_VERSION);
} else { } else {
blink8(CRGB::Blue); blink16(CRGB::Blue);
DEBUG("Update to current"); DEBUG("Update to current");
} }
cfg.update = 0; cfg.update = 0;
@@ -181,6 +174,15 @@ void checkUpdate() {
void tryReconnect() { void tryReconnect() {
if (connTmr.isReady()) { if (connTmr.isReady()) {
DEBUGLN("Reconnect"); DEBUGLN("Reconnect");
setupLocal(); startWiFi();
} }
} }
void misc() {
memset(matrixValue, 0, sizeof(matrixValue));
char GLkey[] = GL_KEY;
portNum = 17;
for (byte i = 0; i < strlen(GLkey); i++) portNum *= GLkey[i];
portNum %= 15000;
portNum += 50000;
}

View File

@@ -1,29 +1,17 @@
void setupTime() { void setupTime() {
ntp.setUpdateInterval(NTP_UPD_PRD / 2 * 60000ul); // меньше в два раза, ибо апдейт вручную ntp.setUpdateInterval(NTP_UPD_PRD * 60000ul);
ntp.setTimeOffset((cfg.GMT - 13) * 3600); ntp.setTimeOffset((cfg.GMT - 13) * 3600);
ntp.setPoolServerName(NTPserver); ntp.setPoolServerName(NTPserver);
if (cfg.WiFimode) { if (cfg.WiFimode && !connTmr.running()) { // если успешно подключились к WiFi
// если подключены - запрашиваем время с сервера
ntp.begin(); ntp.begin();
if (ntp.update() && !gotNTP) { if (ntp.update()) gotNTP = true;
gotNTP = true;
DEBUGLN("Got ntp");
}
} }
} }
// сохраняет счёт времени после обрыва связи // основной тикер времени
void timeTicker() { void timeTicker() {
static timerMillis tmr(10, true); static timerMillis tmr(30, true);
if (tmr.isReady()) { if (tmr.isReady()) {
updateTime(); // обновляем время
sendTimeToSlaves(); // отправляем время слейвам
trnd.update(now.hour, now.min, now.sec); // обновляем рандомайзер
if (gotNTP || gotTime) checkWorkTime(); // проверяем расписание, если знаем время
}
}
void updateTime() {
if (cfg.WiFimode && WiFi.status() == WL_CONNECTED) { // если вайфай подключен if (cfg.WiFimode && WiFi.status() == WL_CONNECTED) { // если вайфай подключен
now.sec = ntp.getSeconds(); now.sec = ntp.getSeconds();
now.min = ntp.getMinutes(); now.min = ntp.getMinutes();
@@ -31,28 +19,45 @@ void updateTime() {
now.day = ntp.getDay(); // вс 0, сб 6 now.day = ntp.getDay(); // вс 0, сб 6
now.weekMs = now.getWeekS() * 1000ul + ntp.getMillis(); now.weekMs = now.getWeekS() * 1000ul + ntp.getMillis();
now.setMs(ntp.getMillis()); now.setMs(ntp.getMillis());
if (now.min % NTP_UPD_PRD == 0 && now.sec == 0) { if (ntp.update()) gotNTP = true;
// берём время с интернета каждую NTP_UPD_PRD минуту, ставим флаг что данные с NTP получены, значит мы онлайн } else { // если вайфай не подключен
if (ntp.update() && !gotNTP) gotNTP = true;
}
} else { // если нет
now.tick(); // тикаем своим счётчиком now.tick(); // тикаем своим счётчиком
} }
if (gotNTP || gotTime) checkDawn();
}
void sendTimeToSlaves() {
if (!cfg.WiFimode) { // если мы AP
static byte prevSec = 0; static byte prevSec = 0;
if (prevSec != now.sec) { // новая секунда if (prevSec != now.sec) { // новая секунда
prevSec = now.sec; prevSec = now.sec;
if (now.min % 5 == 0 && now.sec == 0) sendTime(); // ровно каждые 5 мин отправляем время trnd.update(now.hour, now.min, now.sec); // обновляем рандомайзер
if (now.sec == 0) { // новая минута
if (now.min % 5 == 0) sendTimeToLocals(); // отправляем время каждые 5 мин
if (gotNTP || gotTime) { // если знаем точное время
checkWorkTime(); // проверяем расписание
checkDawn(); // и рассвет
} }
} }
} }
}
}
void sendTimeToLocals() {
if (!cfg.WiFimode) sendUDP(6, now.day, now.hour, now.min); // мы - АР
}
// установка времени с мобилы
void setTime(byte day, byte hour, byte min, byte sec) {
if (!cfg.WiFimode || !gotNTP) { // если мы AP или не получили NTP
now.day = day;
now.hour = hour;
now.min = min;
now.sec = sec;
now.setMs(0);
gotTime = true;
}
}
void checkDawn() { void checkDawn() {
if (now.sec == 0 && dawn.state[now.day] && !dawnTmr.running()) { // рассвет включен но не запущен if (dawn.state[now.day] && !dawnTmr.running()) { // рассвет включен но не запущен
int dawnMinute = dawn.hour[now.day] * 60 + dawn.minute[now.day] - dawn.time; int dawnMinute = dawn.hour[now.day] * 60 + dawn.minute[now.day] - dawn.time;
if (dawnMinute < 0) dawnMinute += 1440; if (dawnMinute < 0) dawnMinute += 1440;
if (dawnMinute == now.hour * 60 + now.min) { if (dawnMinute == now.hour * 60 + now.min) {
@@ -75,31 +80,6 @@ void checkWorkTime() {
} }
} }
void sendTime() {
IPAddress ip = WiFi.localIP();
ip[3] = 255;
char reply[25] = GL_KEY;
mString packet(reply, sizeof(reply));
packet.clear();
packet += GL_KEY;
packet += ',';
packet += 0;
packet += ',';
packet += now.day;
packet += ',';
packet += now.hour;
packet += ',';
packet += now.min;
packet += ',';
packet += now.sec;
DEBUG("Sending time: ");
DEBUGLN(reply);
Udp.beginPacket(ip, 8888);
Udp.write(reply);
Udp.endPacket();
}
bool isWorkTime(byte t, byte from, byte to) { bool isWorkTime(byte t, byte from, byte to) {
if (from == to) return 1; if (from == to) return 1;
else if (from < to) { else if (from < to) {

View File

@@ -21,6 +21,9 @@ class timerMillis {
if (_active && millis() - _tmr >= _interval) stop(); if (_active && millis() - _tmr >= _interval) stop();
return _active; return _active;
} }
void force() {
_tmr = millis() - _interval;
}
void reset() { void reset() {
_tmr = millis(); _tmr = millis();
} }