Merge branch 'development' into dev-arendst

This commit is contained in:
he-so 2020-02-24 19:41:12 +01:00 committed by GitHub
commit dd3d9f3b21
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
43 changed files with 733 additions and 281 deletions

View File

@ -56,6 +56,7 @@ default_envs =
framework = arduino
board = esp01_1m
board_build.flash_mode = dout
board_build.ldscript = eagle.flash.1m.ld
platform = ${core_active.platform}
platform_packages = ${core_active.platform_packages}

View File

@ -135,10 +135,9 @@ build_flags = ${esp82xx_defaults.build_flags}
[core_2_6_3]
; *** Esp8266 core for Arduino version 2.6.3
platform = espressif8266@2.3.2
platform = espressif8266@2.3.3
platform_packages =
build_flags = ${esp82xx_defaults.build_flags}
-Wl,-Teagle.flash.1m.ld
-DBEARSSL_SSL_BASIC
; NONOSDK221
; -DPIO_FRAMEWORK_ARDUINO_ESPRESSIF_SDK221
@ -180,12 +179,10 @@ build_flags = ${esp82xx_defaults.build_flags}
[tasmota_core_stage]
; *** Esp8266 core for Arduino version stable beta
platform = espressif8266@2.3.2
platform = espressif8266@2.3.3
platform_packages = framework-arduinoespressif8266 @ https://github.com/esp8266/Arduino.git#6be561617f645f6a2ae82b8211f6af8c43e834cf
build_flags = ${esp82xx_defaults.build_flags}
-Wl,-Teagle.flash.1m.ld
-DBEARSSL_SSL_BASIC
-DNOPRINTFLOAT
; NONOSDK221
; -DPIO_FRAMEWORK_ARDUINO_ESPRESSIF_SDK221
; NONOSDK22x_190313
@ -226,12 +223,10 @@ build_flags = ${esp82xx_defaults.build_flags}
[core_stage]
; *** Esp8266 core for Arduino version latest beta
platform = espressif8266@2.3.2
platform = espressif8266@2.3.3
platform_packages = framework-arduinoespressif8266 @ https://github.com/esp8266/Arduino.git
board_build.ldscript = eagle.flash.1m.ld
build_flags = ${esp82xx_defaults.build_flags}
-DBEARSSL_SSL_BASIC
-DNOPRINTFLOAT
; NONOSDK221
; -DPIO_FRAMEWORK_ARDUINO_ESPRESSIF_SDK221
; NONOSDK22x_190313

View File

@ -3,6 +3,7 @@ platform = ${common.platform}
platform_packages = ${common.platform_packages}
framework = ${common.framework}
board = ${common.board}
board_build.ldscript = ${common.board_build.ldscript}
board_build.flash_mode = ${common.board_build.flash_mode}
board_build.f_cpu = ${common.board_build.f_cpu}
build_unflags = ${common.build_unflags}

View File

@ -5,6 +5,8 @@
- Revert most wifi connectivity changes introduced in 8.1.0.5 (#7746, #7602, #7621)
- Add initial support for Sensors AHT10 and AHT15 by Martin Wagner (#7596)
- Add support for Wemos Motor Shield V1 by Denis Sborets (#7764)
- Fix Zigbee auto-increment transaction number (#7757)
- Add Zigbee enhanced commands decoding, added ``ZbPing``
### 8.1.0.8 20200212

View File

@ -489,12 +489,15 @@
#define D_CMND_ZIGBEE_FORGET "Forget"
#define D_CMND_ZIGBEE_SAVE "Save"
#define D_CMND_ZIGBEE_LINKQUALITY "LinkQuality"
#define D_CMND_ZIGBEE_ENDPOINT "Endpoint"
#define D_CMND_ZIGBEE_READ "Read"
#define D_CMND_ZIGBEE_SEND "Send"
#define D_JSON_ZIGBEE_ZCL_SENT "ZbZCLSent"
#define D_JSON_ZIGBEE_RECEIVED "ZbReceived"
#define D_JSON_ZIGBEE_RECEIVED_LEGACY "ZigbeeReceived"
#define D_CMND_ZIGBEE_BIND "Bind"
#define D_CMND_ZIGBEE_PING "Ping"
#define D_JSON_ZIGBEE_PING "ZbPing"
// Commands xdrv_25_A4988_Stepper.ino
#define D_CMND_MOTOR "MOTOR"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Посока на вятъра"
#define D_TX20_WIND_DEGREES "Степени на вятъра"
#define D_TX20_WIND_SPEED "Скорост на вятъра"
#define D_TX20_WIND_SPEED_AVG "Средна скорост на вятъра"
#define D_TX20_WIND_SPEED_MIN "Мини. скорост на вятъра"
#define D_TX20_WIND_SPEED_MAX "Макс. скорост на вятъра"
#define D_TX20_NORTH "С"
#define D_TX20_EAST "И"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Směr větru"
#define D_TX20_WIND_DEGREES "Úhel větru"
#define D_TX20_WIND_SPEED "Rychlost větru"
#define D_TX20_WIND_SPEED_AVG "Průměrná rychlost větru"
#define D_TX20_WIND_SPEED_MIN "Minimální rychlost větru"
#define D_TX20_WIND_SPEED_MAX "Maximální rychlost větru"
#define D_TX20_NORTH "S"
#define D_TX20_EAST "V"

View File

@ -503,10 +503,12 @@
#define D_CALIBRATION "Kalibrierung"
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Wind Richtung"
#define D_TX20_WIND_DIRECTION "Windrichtung"
#define D_TX20_WIND_DEGREES "Windrichtung Grad"
#define D_TX20_WIND_SPEED "Windgeschwindigkeit"
#define D_TX20_WIND_SPEED_AVG "Ø Windgeschwindigkeit"
#define D_TX20_WIND_SPEED_MAX "max Windgeschwindigkeit"
#define D_TX20_WIND_SPEED_AVG "Windgeschwindigkeit Ø"
#define D_TX20_WIND_SPEED_MIN "Windgeschwindigkeit Min"
#define D_TX20_WIND_SPEED_MAX "Windgeschwindigkeit Max"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "O"
#define D_TX20_SOUTH "S"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Κατεύθυνση ανέμου"
#define D_TX20_WIND_DEGREES "Βαθμός ανέμου"
#define D_TX20_WIND_SPEED "Ταχύτητα ανέμου"
#define D_TX20_WIND_SPEED_AVG "Μέση ταχύτητα ανέμου"
#define D_TX20_WIND_SPEED_MIN "Ελάχιστη ταχύτητα ανέμου"
#define D_TX20_WIND_SPEED_MAX "Μέγιστη ταχύτητα ανέμου"
#define D_TX20_NORTH "Β"
#define D_TX20_EAST "Α"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Wind Direction"
#define D_TX20_WIND_DEGREES "Wind Degrees"
#define D_TX20_WIND_SPEED "Wind Speed"
#define D_TX20_WIND_SPEED_AVG "Wind Speed Avg"
#define D_TX20_WIND_SPEED_MIN "Wind Speed Min"
#define D_TX20_WIND_SPEED_MAX "Wind Speed Max"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Dirección del Viento"
#define D_TX20_WIND_DEGREES "Ángulo del Viento"
#define D_TX20_WIND_SPEED "Vel. del Viento"
#define D_TX20_WIND_SPEED_AVG "Vel. Prom. del Viento"
#define D_TX20_WIND_SPEED_MIN "Vel. Min. del Viento"
#define D_TX20_WIND_SPEED_MAX "Vel. Max. del Viento"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_TX20.ino
#define D_TX20_WIND_DIRECTION "Direction du vent"
#define D_TX20_WIND_DEGREES "Degré de vent"
#define D_TX20_WIND_SPEED "Vitesse du vent"
#define D_TX20_WIND_SPEED_AVG "Vitesse Moy."
#define D_TX20_WIND_SPEED_MIN "Vitesse Min"
#define D_TX20_WIND_SPEED_MAX "Vitesse Max"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "כיוון הרוח"
#define D_TX20_WIND_DEGREES "זווית הרוח"
#define D_TX20_WIND_SPEED "מהירות הרוח"
#define D_TX20_WIND_SPEED_AVG "מהירות הרוח ממוצעת"
#define D_TX20_WIND_SPEED_MIN "מהירות הרוח היא מינימלית"
#define D_TX20_WIND_SPEED_MAX "מהירות הרוח מקסימלית"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Szélirány"
#define D_TX20_WIND_DEGREES "Szél mértéke"
#define D_TX20_WIND_SPEED "Szélsebesség"
#define D_TX20_WIND_SPEED_AVG "Átlag szélsebesség"
#define D_TX20_WIND_SPEED_MIN "Min. szélsebesség"
#define D_TX20_WIND_SPEED_MAX "Max. szélsebesség"
#define D_TX20_NORTH "É"
#define D_TX20_EAST "K"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Direzione Vento"
#define D_TX20_WIND_DEGREES "Angolo Vento"
#define D_TX20_WIND_SPEED "Velocità Vento"
#define D_TX20_WIND_SPEED_AVG "Velocità Media Vento"
#define D_TX20_WIND_SPEED_MIN "Velocità Minima Vento"
#define D_TX20_WIND_SPEED_MAX "Velocità Massima Vento"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,9 +504,11 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "풍향"
#define D_TX20_WIND_DEGREES "바람 정도"
#define D_TX20_WIND_SPEED "풍속"
#define D_TX20_WIND_SPEED_AVG "평균 풍속"
#define D_TX20_WIND_SPEED_MAX "최대 풍속"
#define D_TX20_WIND_SPEED_MIN "풍속 최소"
#define D_TX20_WIND_SPEED_MAX "풍속 최대"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"
#define D_TX20_SOUTH "S"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Windrichting"
#define D_TX20_WIND_DEGREES "Wind graad"
#define D_TX20_WIND_SPEED "Windsnelheid"
#define D_TX20_WIND_SPEED_AVG "Windsnelheid gemiddeld"
#define D_TX20_WIND_SPEED_MIN "Windsnelhied minimum"
#define D_TX20_WIND_SPEED_MAX "Windsnelhied maximaal"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Kierunek"
#define D_TX20_WIND_DEGREES "Grad"
#define D_TX20_WIND_SPEED "Prędkość"
#define D_TX20_WIND_SPEED_AVG "Średnia prędkość"
#define D_TX20_WIND_SPEED_MIN "Minimalna prędkość"
#define D_TX20_WIND_SPEED_MAX "Maksymalna prędkość"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Direção do vento"
#define D_TX20_WIND_DEGREES "Ângulo do vento"
#define D_TX20_WIND_SPEED "Velocidade do vento"
#define D_TX20_WIND_SPEED_AVG "Velocidade média do vento"
#define D_TX20_WIND_SPEED_MIN "Velocidade do vento Mínima"
#define D_TX20_WIND_SPEED_MAX "Velocidade do vento Máxima"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "L"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Direção do vento"
#define D_TX20_WIND_DEGREES "Ângulo do vento"
#define D_TX20_WIND_SPEED "Velocidade do vento"
#define D_TX20_WIND_SPEED_AVG "Velocidade média do vento"
#define D_TX20_WIND_SPEED_MIN "Velocidade mínima do vento"
#define D_TX20_WIND_SPEED_MAX "Velocidade máxima do vento"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Wind Direction"
#define D_TX20_WIND_DEGREES "Wind Degrees"
#define D_TX20_WIND_SPEED "Wind Speed"
#define D_TX20_WIND_SPEED_AVG "Wind Speed Avg"
#define D_TX20_WIND_SPEED_MIN "Wind Speed Min"
#define D_TX20_WIND_SPEED_MAX "Wind Speed Max"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Smer vetra"
#define D_TX20_WIND_DEGREES "Uhol vetra"
#define D_TX20_WIND_SPEED "Rýchlosť vetra"
#define D_TX20_WIND_SPEED_AVG "Priemerná rýchlosť vetra"
#define D_TX20_WIND_SPEED_MIN "Minimálna rýchlosť vetra"
#define D_TX20_WIND_SPEED_MAX "Maximálna rýchlosť vetra"
#define D_TX20_NORTH "S"
#define D_TX20_EAST "V"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Vindriktning"
#define D_TX20_WIND_DEGREES "Vindvinkel"
#define D_TX20_WIND_SPEED "Vindstyrka"
#define D_TX20_WIND_SPEED_AVG "Vindstyrka medel"
#define D_TX20_WIND_SPEED_MIN "Vindstyrka min"
#define D_TX20_WIND_SPEED_MAX "Vindstyrka max"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "Ö"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Wind Direction"
#define D_TX20_WIND_DEGREES "Wind Degrees"
#define D_TX20_WIND_SPEED "Wind Speed"
#define D_TX20_WIND_SPEED_AVG "Wind Speed Avg"
#define D_TX20_WIND_SPEED_MIN "Wind Speed Min"
#define D_TX20_WIND_SPEED_MAX "Wind Speed Max"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Напрям вітру"
#define D_TX20_WIND_DEGREES "Кут вітру"
#define D_TX20_WIND_SPEED "Швидкість вітру"
#define D_TX20_WIND_SPEED_AVG "Середня швидкість вітру"
#define D_TX20_WIND_SPEED_MIN "Мінімальна швидкість вітру"
#define D_TX20_WIND_SPEED_MAX "Максимальна швидкість вітру"
#define D_TX20_NORTH "Пн"
#define D_TX20_EAST "Сх"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "风向"
#define D_TX20_WIND_DEGREES "风度"
#define D_TX20_WIND_SPEED "风速"
#define D_TX20_WIND_SPEED_AVG "平均风速"
#define D_TX20_WIND_SPEED_MIN "最低风速"
#define D_TX20_WIND_SPEED_MAX "最高风速"
#define D_TX20_NORTH "北"
#define D_TX20_EAST "东"

View File

@ -504,8 +504,10 @@
//xsns_35_tx20.ino
#define D_TX20_WIND_DIRECTION "Wind Direction"
#define D_TX20_WIND_DEGREES "Wind Degrees"
#define D_TX20_WIND_SPEED "Wind Speed"
#define D_TX20_WIND_SPEED_AVG "Wind Speed Avg"
#define D_TX20_WIND_SPEED_MIN "Wind Speed Min"
#define D_TX20_WIND_SPEED_MAX "Wind Speed Max"
#define D_TX20_NORTH "N"
#define D_TX20_EAST "E"

View File

@ -104,7 +104,7 @@ typedef union { // Restricted by MISRA-C Rule 18.4 bu
uint32_t alexa_ct_range : 1; // bit 0 (v8.1.0.2) - SetOption82 - Reduced CT range for Alexa
uint32_t zigbee_use_names : 1; // bit 1 (v8.1.0.4) - SetOption83 - Use FriendlyNames instead of ShortAddresses when possible
uint32_t awsiot_shadow : 1; // bit 2 (v8.1.0.5) - SetOption84 - (AWS IoT) publish MQTT state to a device shadow
uint32_t spare03 : 1;
uint32_t device_groups_enabled : 1; // bit 3 (v8.1.0.9) - SetOption85 - Enable Device Groups
uint32_t spare04 : 1;
uint32_t spare05 : 1;
uint32_t spare06 : 1;
@ -466,13 +466,14 @@ struct SYSCFG {
uint8_t sps30_inuse_hours; // F02
uint8_t hotplug_scan; // F03
uint8_t reserved1; // F04 - reserved for s-hadinger
uint8_t free_f05[191]; // F05
uint32_t keeloq_master_msb; // FC4
uint32_t keeloq_master_lsb; // FC8
uint32_t keeloq_serial; // FCD
uint32_t keeloq_count; // FD0
uint8_t free_f05[183]; // F05
uint32_t keeloq_master_msb; // FBC
uint32_t keeloq_master_lsb; // FC0
uint32_t keeloq_serial; // FC4
uint32_t keeloq_count; // FC8
uint32_t device_group_share_in; // FCC - Bitmask of device group items imported
uint32_t device_group_share_out; // FD0 - Bitmask of device group items exported
uint32_t bootcount_reset_time; // FD4
int adc_param4; // FD8
uint32_t shutter_button[MAX_KEYS]; // FDC

View File

@ -277,6 +277,23 @@ bool RtcRebootValid(void)
/*********************************************************************************************\
* Config - Flash
*
* Tasmota 1M flash usage
* 0x00000000 - Unzipped binary bootloader
* 0x00001000 - Unzipped binary code start
* ::::
* 0x000xxxxx - Unzipped binary code end
* 0x000x1000 - First page used by Core OTA
* ::::
* 0x000F3000 - Tasmota Quick Power Cycle counter (SETTINGS_LOCATION - CFG_ROTATES) - First four bytes only
* 0x000F4000 - First Tasmota rotating settings page
* ::::
* 0x000FA000 - Last Tasmota rotating settings page = Last page used by Core OTA
* 0x000FB000 - Core SPIFFS end = Core EEPROM = Tasmota settings page during OTA and when no flash rotation is active (SETTINGS_LOCATION)
* 0x000FC000 - SDK - Uses first 128 bytes for phy init data mirrored by Core in RAM. See core_esp8266_phy.cpp phy_init_data[128] = Core user_rf_cal_sector
* 0x000FD000 - SDK - Uses scattered bytes from 0x340 (iTead use as settings storage from 0x000FD000)
* 0x000FE000 - SDK - Uses scattered bytes from 0x340 (iTead use as mirrored settings storage from 0x000FE000)
* 0x000FF000 - SDK - Uses at least first 32 bytes of this page - Tasmota Zigbee persistence from 0x000FF800 to 0x000FFFFF
\*********************************************************************************************/
extern "C" {
@ -745,8 +762,17 @@ void SettingsErase(uint8_t type)
_sectorStart = SETTINGS_LOCATION - CFG_ROTATES; // Tasmota and SDK parameter area (0x0F3xxx - 0x0FFFFF)
_sectorEnd = ESP.getFlashChipSize() / SPI_FLASH_SEC_SIZE; // Flash size as seen by SDK
}
AddLog_P2(LOG_LEVEL_DEBUG, PSTR(D_LOG_APPLICATION D_ERASE " %d " D_UNIT_SECTORS), _sectorEnd - _sectorStart);
#ifdef USE_WIFI_SDK_ERASE
else if (4 == type) {
_sectorStart = SETTINGS_LOCATION +1; // SDK phy area and Core calibration sector (0x0FC000)
_sectorEnd = _sectorStart +1; // SDK end of phy area and Core calibration sector (0x0FCFFF)
}
else if (5 == type) {
_sectorStart = (ESP.getFlashChipRealSize() / SPI_FLASH_SEC_SIZE) -4; // SDK phy area and Core calibration sector (0xxFC000)
_sectorEnd = _sectorStart +1; // SDK end of phy area and Core calibration sector (0xxFCFFF)
}
#endif // USE_WIFI_SDK_ERASE
AddLog_P2(LOG_LEVEL_DEBUG, PSTR(D_LOG_APPLICATION D_ERASE " from 0x%08X to 0x%08X"), _sectorStart * SPI_FLASH_SEC_SIZE, (_sectorEnd * SPI_FLASH_SEC_SIZE) -1);
// EspErase(_sectorStart, _sectorEnd); // Arduino core and SDK - erases flash as seen by SDK
EsptoolErase(_sectorStart, _sectorEnd); // Esptool - erases flash completely
@ -755,11 +781,21 @@ void SettingsErase(uint8_t type)
void SettingsSdkErase(void)
{
WiFi.disconnect(true); // Delete SDK wifi config
WiFi.disconnect(false); // Delete SDK wifi config
SettingsErase(1);
delay(1000);
}
#ifdef USE_WIFI_SDK_ERASE
void SettingsSdkWifiErase(void)
{
WiFi.disconnect(false); // Delete SDK wifi config
SettingsErase(4);
SettingsErase(5);
delay(200);
}
#endif // USE_WIFI_SDK_ERASE
/********************************************************************************************/
void SettingsDefault(void)

View File

@ -620,12 +620,17 @@ void WifiConnect(void)
// Re-enabled from 6.3.0.7 with ESP.restart replaced by ESP.reset
void WifiDisconnect(void)
{
#ifdef USE_WIFI_SDK_ERASE // Do not enable with DeepSleep as it will wear out flash
SettingsSdkWifiErase();
#else
// Courtesy of EspEasy
WiFi.persistent(true); // use SDK storage of SSID/WPA parameters
ETS_UART_INTR_DISABLE();
wifi_station_disconnect(); // this will store empty ssid/wpa into sdk storage
ETS_UART_INTR_ENABLE();
WiFi.persistent(false); // Do not use SDK storage of SSID/WPA parameters
delay(100); // Flush anything in the network buffers.
#endif // USE_WIFI_SDK_ERASE
}
void WifiShutdown(void)

View File

@ -398,7 +398,7 @@ void MqttPublishPrefixTopic_P(uint32_t prefix, const char* subtopic, bool retain
free(mqtt_save);
bool result = MqttClient.publish(romram, mqtt_data, false);
AddLog_P2(LOG_LEVEL_INFO, PSTR(D_LOG_MQTT "Updated shadow: %s"), romram);
AddLog_P2(LOG_LEVEL_DEBUG, PSTR(D_LOG_MQTT "Updated shadow: %s"), romram);
yield(); // #3313
}
#endif // USE_MQTT_AWS_IOT

View File

@ -296,6 +296,7 @@ bool DomoticzMqttData(void)
found = true;
} else
#endif // USE_SHUTTER
#ifdef USE_LIGHT
if (iscolordimmer && 10 == nvalue) { // Color_SetColor
// https://www.domoticz.com/wiki/Domoticz_API/JSON_URL%27s#Set_a_light_to_a_certain_color_or_color_temperature
JsonObject& color = domoticz["Color"];
@ -333,8 +334,9 @@ bool DomoticzMqttData(void)
snprintf_P(XdrvMailbox.topic, XdrvMailbox.index, PSTR("/" D_CMND_DIMMER));
snprintf_P(XdrvMailbox.data, XdrvMailbox.data_len, PSTR("%d"), nvalue);
found = true;
}
else if (1 == nvalue || 0 == nvalue) {
} else
#endif // USE_LIGHT
if (1 == nvalue || 0 == nvalue) {
if (((power >> i) &1) == (power_t)nvalue) {
return true; // Stop loop
}

View File

@ -21,7 +21,7 @@
// contains some definitions for functions used before their declarations
void ZigbeeZCLSend(uint16_t dtsAddr, uint16_t clusterId, uint8_t endpoint, uint8_t cmdId, bool clusterSpecific, const uint8_t *msg, size_t len, bool disableDefResp = true, uint8_t transacId = 1);
void ZigbeeZCLSend(uint16_t dtsAddr, uint16_t clusterId, uint8_t endpoint, uint8_t cmdId, bool clusterSpecific, const uint8_t *msg, size_t len, bool needResponse, uint8_t transacId);
// Get an JSON attribute, with case insensitive key search

View File

@ -19,6 +19,10 @@
#ifdef USE_ZIGBEE
#ifndef ZIGBEERECEIVED
#define ZIGBEERECEIVED 1
#endif
#include <vector>
#include <map>
@ -49,6 +53,8 @@ typedef struct Z_Device {
// json buffer used for attribute reporting
DynamicJsonBuffer *json_buffer;
JsonObject *json;
// sequence number for Zigbee frames
uint8_t seqNumber;
} Z_Device;
// All devices are stored in a Vector
@ -96,6 +102,9 @@ public:
// device just seen on the network, update the lastSeen field
void updateLastSeen(uint16_t shortaddr);
// get next sequence number for (increment at each all)
uint8_t getNextSeqNumber(uint16_t shortaddr);
// Dump json
String dump(uint32_t dump_mode, uint16_t status_shortaddr = 0) const;
@ -133,6 +142,7 @@ public:
private:
std::vector<Z_Device> _devices = {};
uint32_t _saveTimer = 0;
uint8_t _seqNumber = 0; // global seqNumber if device is unknown
template < typename T>
static bool findInVector(const std::vector<T> & vecOfElements, const T & element);
@ -226,7 +236,9 @@ Z_Device & Z_Devices::createDeviceEntry(uint16_t shortaddr, uint64_t longaddr) {
std::vector<uint32_t>(),
0,0,0,0,
nullptr,
nullptr, nullptr };
nullptr, nullptr,
0, // seqNumber
};
device.json_buffer = new DynamicJsonBuffer();
_devices.push_back(device);
dirty();
@ -532,6 +544,19 @@ void Z_Devices::updateLastSeen(uint16_t shortaddr) {
_updateLastSeen(device);
}
// get the next sequance number for the device, or use the global seq number if device is unknown
uint8_t Z_Devices::getNextSeqNumber(uint16_t shortaddr) {
int32_t short_found = findShortAddr(shortaddr);
if (short_found >= 0) {
Z_Device &device = getShortAddr(shortaddr);
device.seqNumber += 1;
return device.seqNumber;
} else {
_seqNumber += 1;
return _seqNumber;
}
}
// Per device timers
//
// Reset the timer for a specific device
@ -704,18 +729,22 @@ void Z_Devices::jsonPublishFlush(uint16_t shortaddr) {
Response_P(PSTR("{\"" D_JSON_ZIGBEE_RECEIVED "\":{\"%s\":%s}}"), fname->c_str(), msg.c_str());
MqttPublishPrefixTopic_P(TELE, PSTR(D_RSLT_SENSOR));
XdrvRulesProcess();
#if ZIGBEERECEIVED
// DEPRECATED TODO
Response_P(PSTR("{\"" D_JSON_ZIGBEE_RECEIVED_LEGACY "\":{\"%s\":%s}}"), fname->c_str(), msg.c_str());
MqttPublishPrefixTopic_P(TELE, PSTR(D_RSLT_SENSOR));
XdrvRulesProcess();
#endif
} else {
Response_P(PSTR("{\"" D_JSON_ZIGBEE_RECEIVED "\":{\"0x%04X\":%s}}"), shortaddr, msg.c_str());
MqttPublishPrefixTopic_P(TELE, PSTR(D_RSLT_SENSOR));
XdrvRulesProcess();
#if ZIGBEERECEIVED
// DEPRECATED TODO
Response_P(PSTR("{\"" D_JSON_ZIGBEE_RECEIVED_LEGACY "\":{\"0x%04X\":%s}}"), shortaddr, msg.c_str());
MqttPublishPrefixTopic_P(TELE, PSTR(D_RSLT_SENSOR));
XdrvRulesProcess();
#endif
}
// MqttPublishPrefixTopic_P(TELE, PSTR(D_RSLT_SENSOR));
// XdrvRulesProcess();

View File

@ -486,18 +486,8 @@ void ZCLFrame::parseReadAttributes(JsonObject& json, uint8_t offset) {
// Parse non-normalized attributes
// The key is "s_" followed by 16 bits clusterId, "_" followed by 8 bits command id
void ZCLFrame::parseClusterSpecificCommand(JsonObject& json, uint8_t offset) {
uint32_t i = offset;
uint32_t len = _payload.len();
char attrid_str[12];
snprintf_P(attrid_str, sizeof(attrid_str), PSTR("%04X!%02X"), _cluster_id, _cmd_id);
char hex_char[_payload.len()*2+2];
ToHex_P((unsigned char*)_payload.getBuffer(), _payload.len(), hex_char, sizeof(hex_char));
json[attrid_str] = hex_char;
convertClusterSpecific(json, _cluster_id, _cmd_id, _frame_control.b.direction, _payload);
}
// return value:

View File

@ -19,34 +19,81 @@
#ifdef USE_ZIGBEE
//typedef int32_t (*Z_AttrConverter)(uint16_t shortaddr, JsonObject& json, const char *name, JsonVariant& value, const char *new_name, void * param);
typedef struct Z_CommandConverter {
const char * tasmota_cmd;
const char * zcl_cmd;
uint16_t cluster;
uint8_t cmd; // normally 8 bits, 0xFF means it's a parameter
uint8_t direction; // direction of the command. 0x01 client->server, 0x02 server->client, 0x03 both
const char * param;
} Z_CommandConverter;
typedef struct Z_XYZ_Var { // Holds values for vairables X, Y and Z
uint32_t x = 0;
uint32_t y = 0;
uint32_t z = 0;
uint8_t x_type = 0; // 0 = no value, 1 = 1 bytes, 2 = 2 bytes
uint8_t y_type = 0;
uint8_t z_type = 0;
} Z_XYZ_Var;
// list of post-processing directives
const Z_CommandConverter Z_Commands[] = {
{ "Power", "0006!xx" }, // 0=Off, 1=On, 2=Toggle
{ "Dimmer", "0008!04/xx0A00" }, // Move to Level with On/Off, xx=0..254 (255 is invalid)
{ "Dimmer+", "0008!06/001902" }, // Step up by 10%, 0.2 secs
{ "Dimmer-", "0008!06/011902" }, // Step down by 10%, 0.2 secs
{ "DimmerStop", "0008!03" }, // Stop any Dimmer animation
{ "ResetAlarm", "0009!00/xxyyyy" }, // Reset alarm (alarm code + cluster identifier)
{ "ResetAllAlarms","0009!01" }, // Reset all alarms
{ "Hue", "0300!00/xx000A00" }, // Move to Hue, shortest time, 1s
{ "Sat", "0300!03/xx0A00" }, // Move to Sat
{ "HueSat", "0300!06/xxyy0A00" }, // Hue, Sat
{ "Color", "0300!07/xxxxyyyy0A00" }, // x, y (uint16)
{ "CT", "0300!0A/xxxx0A00" }, // Color Temperature Mireds (uint16)
{ "Shutter", "0102!xx" },
{ "ShutterOpen", "0102!00" },
{ "ShutterClose", "0102!01" },
{ "ShutterStop", "0102!02" },
{ "ShutterLift", "0102!05xx" }, // Lift percentage, 0%=open, 100%=closed
{ "ShutterTilt", "0102!08xx" }, // Tilt percentage
// Group adress commands
{ "AddGroup", 0x0004, 0x00, 0x01, "xxxx00" }, // Add group id, group name is not supported
{ "ViewGroup", 0x0004, 0x01, 0x01, "xxxx" }, // Ask for the group name
{ "GetGroup", 0x0004, 0x02, 0x01, "01xxxx" }, // Get one group membership
{ "GetAllGroups", 0x0004, 0x02, 0x01, "00" }, // Get all groups membership
{ "RemoveGroup", 0x0004, 0x03, 0x01, "xxxx" }, // Remove one group
{ "RemoveAllGroups",0x0004, 0x04, 0x01, "" }, // Remove all groups
// Light & Shutter commands
{ "Power", 0x0006, 0xFF, 0x01, "" }, // 0=Off, 1=On, 2=Toggle
{ "Dimmer", 0x0008, 0x04, 0x01, "xx0A00" }, // Move to Level with On/Off, xx=0..254 (255 is invalid)
{ "Dimmer+", 0x0008, 0x06, 0x01, "001902" }, // Step up by 10%, 0.2 secs
{ "Dimmer-", 0x0008, 0x06, 0x01, "011902" }, // Step down by 10%, 0.2 secs
{ "DimmerStop", 0x0008, 0x03, 0x01, "" }, // Stop any Dimmer animation
{ "ResetAlarm", 0x0009, 0x00, 0x01, "xxyyyy" }, // Reset alarm (alarm code + cluster identifier)
{ "ResetAllAlarms", 0x0009, 0x01, 0x01, "" }, // Reset all alarms
{ "Hue", 0x0300, 0x00, 0x01, "xx000A00" }, // Move to Hue, shortest time, 1s
{ "Sat", 0x0300, 0x03, 0x01, "xx0A00" }, // Move to Sat
{ "HueSat", 0x0300, 0x06, 0x01, "xxyy0A00" }, // Hue, Sat
{ "Color", 0x0300, 0x07, 0x01, "xxxxyyyy0A00" }, // x, y (uint16)
{ "CT", 0x0300, 0x0A, 0x01, "xxxx0A00" }, // Color Temperature Mireds (uint16)
{ "ShutterOpen", 0x0102, 0x00, 0x01, "" },
{ "ShutterClose", 0x0102, 0x01, 0x01, "" },
{ "ShutterStop", 0x0102, 0x02, 0x01, "" },
{ "ShutterLift", 0x0102, 0x05, 0x01, "xx" }, // Lift percentage, 0%=open, 100%=closed
{ "ShutterTilt", 0x0102, 0x08, 0x01, "xx" }, // Tilt percentage
{ "Shutter", 0x0102, 0xFF, 0x01, "" },
// Blitzwolf PIR
{ "Occupancy", 0xEF00, 0x01, 0x01, "xx"}, // Specific decoder for Blitzwolf PIR, empty name means special treatment
// Decoders only - normally not used to send, and names may be masked by previous definitions
{ "Dimmer", 0x0008, 0x00, 0x01, "xx" },
{ "DimmerMove", 0x0008, 0x01, 0x01, "xx0A" },
{ "DimmerStep", 0x0008, 0x02, 0x01, "xx190A00" },
{ "DimmerMove", 0x0008, 0x05, 0x01, "xx0A" },
{ "Dimmer+", 0x0008, 0x06, 0x01, "00" },
{ "Dimmer-", 0x0008, 0x06, 0x01, "01" },
{ "DimmerStop", 0x0008, 0x07, 0x01, "" },
{ "HueMove", 0x0300, 0x01, 0x01, "xx19" },
{ "HueStep", 0x0300, 0x02, 0x01, "xx190A00" },
{ "SatMove", 0x0300, 0x04, 0x01, "xx19" },
{ "SatStep", 0x0300, 0x05, 0x01, "xx190A" },
{ "ColorMove", 0x0300, 0x08, 0x01, "xxxxyyyy" },
{ "ColorStep", 0x0300, 0x09, 0x01, "xxxxyyyy0A00" },
// Tradfri
{ "ArrowClick", 0x0005, 0x07, 0x01, "xx" }, // xx == 0x01 = left, 0x00 = right
{ "ArrowHold", 0x0005, 0x08, 0x01, "xx" }, // xx == 0x01 = left, 0x00 = right
{ "ArrowRelease", 0x0005, 0x09, 0x01, "" },
// IAS - Intruder Alarm System + leak/fire detection
{ "ZoneStatusChange",0x0500, 0x00, 0x02, "xxxxyyzz" }, // xxxx = zone status, yy = extended status, zz = zone id, Delay is ignored
// responses for Group cluster commands
{ "AddGroupResp", 0x0004, 0x00, 0x02, "xxyyyy" }, // xx = status, yy = group id
{ "ViewGroupResp", 0x0004, 0x01, 0x02, "xxyyyy" }, // xx = status, yy = group id, name ignored
{ "GetGroupResp", 0x0004, 0x02, 0x02, "xxyyzzzz" }, // xx = capacity, yy = count, zzzz = first group id, following groups ignored
{ "RemoveGroup", 0x0004, 0x03, 0x02, "xxyyyy" }, // xx = status, yy = group id
};
#define ZLE(x) ((x) & 0xFF), ((x) >> 8) // Little Endian
// Below are the attributes we wand to read from each cluster
@ -55,6 +102,7 @@ const uint8_t CLUSTER_0008[] = { ZLE(0x0000) }; // CurrentLevel
const uint8_t CLUSTER_0009[] = { ZLE(0x0000) }; // AlarmCount
const uint8_t CLUSTER_0300[] = { ZLE(0x0000), ZLE(0x0001), ZLE(0x0003), ZLE(0x0004), ZLE(0x0007) }; // Hue, Sat, X, Y, CT
// This callback is registered after a cluster specific command and sends a read command for the same cluster
int32_t Z_ReadAttrCallback(uint16_t shortaddr, uint16_t cluster, uint16_t endpoint, uint32_t value) {
size_t attrs_len = 0;
const uint8_t* attrs = nullptr;
@ -78,11 +126,10 @@ int32_t Z_ReadAttrCallback(uint16_t shortaddr, uint16_t cluster, uint16_t endpoi
break;
}
if (attrs) {
ZigbeeZCLSend(shortaddr, cluster, endpoint, ZCL_READ_ATTRIBUTES, false, attrs, attrs_len, false /* we do want a response */);
ZigbeeZCLSend(shortaddr, cluster, endpoint, ZCL_READ_ATTRIBUTES, false, attrs, attrs_len, true /* we do want a response */, zigbee_devices.getNextSeqNumber(shortaddr));
}
}
// set a timer to read back the value in the future
void zigbeeSetCommandTimer(uint16_t shortaddr, uint16_t cluster, uint16_t endpoint) {
uint32_t wait_ms = 0;
@ -105,22 +152,182 @@ void zigbeeSetCommandTimer(uint16_t shortaddr, uint16_t cluster, uint16_t endpoi
}
}
const __FlashStringHelper* zigbeeFindCommand(const char *command) {
char parm_uc[16]; // used to convert JSON keys to uppercase
// returns true if char is 'x', 'y' or 'z'
inline bool isXYZ(char c) {
return (c >= 'x') && (c <= 'z');
}
// returns the Hex value of a digit [0-9A-Fa-f]
// return: 0x00-0x0F
// or -1 if cannot be parsed
inline int8_t hexValue(char c) {
if ((c >= '0') && (c <= '9')) {
return c - '0';
}
if ((c >= 'A') && (c <= 'F')) {
return 10 + c - 'A';
}
if ((c >= 'a') && (c <= 'f')) {
return 10 + c - 'a';
}
return -1;
}
// Parse a Big Endian suite of max_len digits, or stops when a non-hex digit is found
uint32_t parseHex_P(const char **data, size_t max_len = 8) {
uint32_t ret = 0;
for (uint32_t i = 0; i < max_len; i++) {
int8_t v = hexValue(pgm_read_byte(*data));
if (v < 0) { break; } // non hex digit, we stop parsing
ret = (ret << 4) | v;
*data += 1;
}
return ret;
}
// Parse a model like "xxyy00"
// and fill x, y and z values
// Little Endian encoding
// On exit, xyz is updated, and x_type, y_type, z_type contain the number of bytes read for each
void parseXYZ(const char *model, const SBuffer &payload, struct Z_XYZ_Var *xyz) {
const char *p = model; // pointer to the model character
uint32_t v = 0; // index in the payload bytes buffer
char c = pgm_read_byte(p); // cur char
while (c) {
char c1 = pgm_read_byte(p+1); // next char
if (!c1) { break; } // unexpected end of model
if (isXYZ(c) && (c == c1) && (v < payload.len())) { // if char is [x-z] and followed by same char
uint8_t val = payload.get8(v);
switch (c) {
case 'x':
xyz->x = xyz->x | (val << (xyz->x_type * 8));
xyz->x_type++;
break;
case 'y':
xyz->y = xyz->y | (val << (xyz->y_type * 8));
xyz->y_type++;
break;
case 'z':
xyz->z = xyz->z | (val << (xyz->z_type * 8));
xyz->z_type++;
break;
}
}
p += 2;
v++;
c = pgm_read_byte(p);
}
}
// works on big endiand hex only
// Returns if found:
// - cluster number
// - command number or 0xFF if command is part of the variable part
// - the payload in the form of a HEX string with x/y/z variables
// Parse a cluster specific command, and try to convert into human readable
void convertClusterSpecific(JsonObject& json, uint16_t cluster, uint8_t cmd, bool direction, const SBuffer &payload) {
size_t hex_char_len = payload.len()*2+2;
char *hex_char = (char*) malloc(hex_char_len);
if (!hex_char) { return; }
ToHex_P((unsigned char*)payload.getBuffer(), payload.len(), hex_char, hex_char_len);
const __FlashStringHelper* command_name = nullptr;
Z_XYZ_Var xyz;
//AddLog_P2(LOG_LEVEL_INFO, PSTR(">>> len = %d - %02X%02X%02X"), payload.len(), payload.get8(0), payload.get8(1), payload.get8(2));
for (uint32_t i = 0; i < sizeof(Z_Commands) / sizeof(Z_Commands[0]); i++) {
const Z_CommandConverter *conv = &Z_Commands[i];
if (conv->cluster == cluster) {
// cluster match
if ((0xFF == conv->cmd) || (cmd == conv->cmd)) {
// cmd match
if ((direction && (conv->direction & 0x02)) || (!direction && (conv->direction & 0x01))) {
// check if we have a match for params too
// Match if:
// - payload exactly matches conv->param (conv->param may be longer)
// - payload matches conv->param until 'x', 'y' or 'z'
const char * p = conv->param;
//AddLog_P2(LOG_LEVEL_INFO, PSTR(">>>++1 param = %s"), p);
bool match = true;
for (uint8_t i = 0; i < payload.len(); i++) {
const char c1 = pgm_read_byte(p);
const char c2 = pgm_read_byte(p+1);
//AddLog_P2(LOG_LEVEL_INFO, PSTR(">>>++2 c1 = %c, c2 = %c"), c1, c2);
if ((0x00 == c1) || isXYZ(c1)) {
break;
}
const char * p2 = p;
uint32_t nextbyte = parseHex_P(&p2, 2);
//AddLog_P2(LOG_LEVEL_INFO, PSTR(">>>++3 parseHex_P = %02X"), nextbyte);
if (nextbyte != payload.get8(i)) {
match = false;
break;
}
p += 2;
}
if (match) {
command_name = (const __FlashStringHelper*) conv->tasmota_cmd;
parseXYZ(conv->param, payload, &xyz);
if (0xFF == conv->cmd) {
// shift all values
xyz.z = xyz.y;
xyz.z_type = xyz.y_type;
xyz.y = xyz.x;
xyz.y_type = xyz.x_type;
xyz.x = cmd;
xyz.x_type = 1; // 1 byte
}
break;
}
}
}
}
}
// always report attribute in raw format
// Format: "0001!06": "00" = "<cluster>!<cmd>": "<payload>" for commands to devices
// Format: "0004<00": "00" = "<cluster><<cmd>": "<payload>" for commands to devices
char attrid_str[12];
snprintf_P(attrid_str, sizeof(attrid_str), PSTR("%04X%c%02X"), cluster, direction ? '<' : '!', cmd);
json[attrid_str] = hex_char;
free(hex_char);
if (command_name) {
if (0 == xyz.x_type) {
json[command_name] = true; // no parameter
} else if (0 == xyz.y_type) {
json[command_name] = xyz.x; // 1 parameter
} else {
// multiple answers, create an array
JsonArray &arr = json.createNestedArray(command_name);
arr.add(xyz.x);
arr.add(xyz.y);
if (xyz.z_type) {
arr.add(xyz.z);
}
}
}
}
// Find the command details by command name
// If not found:
// - returns nullptr
const __FlashStringHelper* zigbeeFindCommand(const char *command, uint16_t *cluster, uint16_t *cmd) {
for (uint32_t i = 0; i < sizeof(Z_Commands) / sizeof(Z_Commands[0]); i++) {
const Z_CommandConverter *conv = &Z_Commands[i];
if (0 == strcasecmp_P(command, conv->tasmota_cmd)) {
return (const __FlashStringHelper*) conv->zcl_cmd;
*cluster = conv->cluster;
*cmd = conv->cmd;
return (const __FlashStringHelper*) conv->param;
}
}
return nullptr;
}
inline bool isXYZ(char c) {
return (c >= 'x') && (c <= 'z');
}
// take the lower 4 bits and turn it to an hex char
inline char hexDigit(uint32_t h) {
uint32_t nybble = h & 0x0F;

View File

@ -33,6 +33,7 @@ const uint8_t ZIGBEE_STATUS_NODE_DESC = 31; // Node descriptor
const uint8_t ZIGBEE_STATUS_ACTIVE_EP = 32; // Endpoints descriptor
const uint8_t ZIGBEE_STATUS_SIMPLE_DESC = 33; // Simple Descriptor (clusters)
const uint8_t ZIGBEE_STATUS_DEVICE_INDICATION = 34; // Device announces its address
const uint8_t ZIGBEE_STATUS_DEVICE_IEEE = 35; // Request of device address
const uint8_t ZIGBEE_STATUS_CC_VERSION = 50; // Status: CC2530 ZNP Version
const uint8_t ZIGBEE_STATUS_CC_INFO = 51; // Status: CC2530 Device Configuration
const uint8_t ZIGBEE_STATUS_UNSUPPORTED_VERSION = 98; // Unsupported ZNP version

View File

@ -176,15 +176,24 @@ int32_t Z_ReceivePermitJoinStatus(int32_t res, const class SBuffer &buf) {
return -1;
}
// Send ZDO_IEEE_ADDR_REQ request to get IEEE long address
void Z_SendIEEEAddrReq(uint16_t shortaddr) {
uint8_t IEEEAddrReq[] = { Z_SREQ | Z_ZDO, ZDO_IEEE_ADDR_REQ,
Z_B0(shortaddr), Z_B1(shortaddr), 0x00, 0x00 };
ZigbeeZNPSend(IEEEAddrReq, sizeof(IEEEAddrReq));
}
// Send ACTIVE_EP_REQ to collect active endpoints for this address
void Z_SendActiveEpReq(uint16_t shortaddr) {
uint8_t ActiveEpReq[] = { Z_SREQ | Z_ZDO, ZDO_ACTIVE_EP_REQ,
Z_B0(shortaddr), Z_B1(shortaddr), Z_B0(shortaddr), Z_B1(shortaddr) };
uint8_t NodeDescReq[] = { Z_SREQ | Z_ZDO, ZDO_NODE_DESC_REQ,
Z_B0(shortaddr), Z_B1(shortaddr), Z_B0(shortaddr), Z_B1(shortaddr) };
ZigbeeZNPSend(ActiveEpReq, sizeof(ActiveEpReq));
// uint8_t NodeDescReq[] = { Z_SREQ | Z_ZDO, ZDO_NODE_DESC_REQ,
// Z_B0(shortaddr), Z_B1(shortaddr), Z_B0(shortaddr), Z_B1(shortaddr) };
//ZigbeeZNPSend(NodeDescReq, sizeof(NodeDescReq)); Not sure this is useful
}
@ -335,6 +344,40 @@ int32_t Z_ReceiveSimpleDesc(int32_t res, const class SBuffer &buf) {
return -1;
}
int32_t Z_ReceiveIEEEAddr(int32_t res, const class SBuffer &buf) {
uint8_t status = buf.get8(2);
Z_IEEEAddress ieeeAddr = buf.get64(3);
Z_ShortAddress nwkAddr = buf.get16(11);
// uint8_t startIndex = buf.get8(13);
// uint8_t numAssocDev = buf.get8(14);
if (0 == status) { // SUCCESS
zigbee_devices.updateDevice(nwkAddr, ieeeAddr);
char hex[20];
Uint64toHex(ieeeAddr, hex, 64);
Response_P(PSTR("{\"" D_JSON_ZIGBEE_STATE "\":{"
"\"Status\":%d,\"IEEEAddr\":\"%s\",\"ShortAddr\":\"0x%04X\""
"}}"),
ZIGBEE_STATUS_DEVICE_IEEE, hex, nwkAddr
);
MqttPublishPrefixTopic_P(RESULT_OR_TELE, PSTR(D_JSON_ZIGBEEZCL_RECEIVED));
XdrvRulesProcess();
// Ping response
const String * friendlyName = zigbee_devices.getFriendlyName(nwkAddr);
if (friendlyName) {
Response_P(PSTR("{\"" D_JSON_ZIGBEE_PING "\":{\"" D_JSON_ZIGBEE_DEVICE "\":\"0x%04X\""
",\"" D_JSON_ZIGBEE_NAME "\":\"%s\"}}"), nwkAddr, friendlyName->c_str());
} else {
Response_P(PSTR("{\"" D_JSON_ZIGBEE_PING "\":{\"" D_JSON_ZIGBEE_DEVICE "\":\"0x%04X\"}}"), nwkAddr);
}
MqttPublishPrefixTopic_P(RESULT_OR_TELE, PSTR(D_JSON_ZIGBEEZCL_RECEIVED));
XdrvRulesProcess();
}
return -1;
}
int32_t Z_ReceiveEndDeviceAnnonce(int32_t res, const class SBuffer &buf) {
Z_ShortAddress srcAddr = buf.get16(2);
Z_ShortAddress nwkAddr = buf.get16(4);
@ -451,6 +494,8 @@ int32_t Z_ReceiveAfIncomingMessage(int32_t res, const class SBuffer &buf) {
AddLog_P2(LOG_LEVEL_DEBUG, PSTR(D_LOG_ZIGBEE D_JSON_ZIGBEEZCL_RAW_RECEIVED ": {\"0x%04X\":%s}"), srcaddr, msg.c_str());
zcl_received.postProcessAttributes(srcaddr, json);
// Add Endpoint
json[F(D_CMND_ZIGBEE_ENDPOINT)] = srcendpoint;
// Add linkquality
json[F(D_CMND_ZIGBEE_LINKQUALITY)] = linkquality;
@ -482,6 +527,7 @@ ZBM(AREQ_END_DEVICE_TC_DEV_IND, Z_AREQ | Z_ZDO, ZDO_TC_DEV_IND) // 45CA
ZBM(AREQ_PERMITJOIN_OPEN_XX, Z_AREQ | Z_ZDO, ZDO_PERMIT_JOIN_IND ) // 45CB
ZBM(AREQ_ZDO_ACTIVEEPRSP, Z_AREQ | Z_ZDO, ZDO_ACTIVE_EP_RSP) // 4585
ZBM(AREQ_ZDO_SIMPLEDESCRSP, Z_AREQ | Z_ZDO, ZDO_SIMPLE_DESC_RSP) // 4584
ZBM(AREQ_ZDO_IEEE_ADDR_RSP, Z_AREQ | Z_ZDO, ZDO_IEEE_ADDR_RSP) // 4581
const Z_Dispatcher Z_DispatchTable[] PROGMEM = {
{ AREQ_AF_INCOMING_MESSAGE, &Z_ReceiveAfIncomingMessage },
@ -491,6 +537,7 @@ const Z_Dispatcher Z_DispatchTable[] PROGMEM = {
{ AREQ_ZDO_NODEDESCRSP, &Z_ReceiveNodeDesc },
{ AREQ_ZDO_ACTIVEEPRSP, &Z_ReceiveActiveEp },
{ AREQ_ZDO_SIMPLEDESCRSP, &Z_ReceiveSimpleDesc },
{ AREQ_ZDO_IEEE_ADDR_RSP, &Z_ReceiveIEEEAddr },
};
int32_t Z_Recv_Default(int32_t res, const class SBuffer &buf) {

View File

@ -33,19 +33,22 @@ const char kZbCommands[] PROGMEM = D_PRFX_ZB "|" // prefix
D_CMND_ZIGBEEZNPSEND "|" D_CMND_ZIGBEE_PERMITJOIN "|"
D_CMND_ZIGBEE_STATUS "|" D_CMND_ZIGBEE_RESET "|" D_CMND_ZIGBEE_SEND "|"
D_CMND_ZIGBEE_PROBE "|" D_CMND_ZIGBEE_READ "|" D_CMND_ZIGBEEZNPRECEIVE "|"
D_CMND_ZIGBEE_FORGET "|" D_CMND_ZIGBEE_SAVE "|" D_CMND_ZIGBEE_NAME "|" D_CMND_ZIGBEE_BIND ;
D_CMND_ZIGBEE_FORGET "|" D_CMND_ZIGBEE_SAVE "|" D_CMND_ZIGBEE_NAME "|" D_CMND_ZIGBEE_BIND "|"
D_CMND_ZIGBEE_PING ;
const char kZigbeeCommands[] PROGMEM = D_PRFX_ZIGBEE "|" // legacy prefix -- deprecated
D_CMND_ZIGBEEZNPSEND "|" D_CMND_ZIGBEE_PERMITJOIN "|"
D_CMND_ZIGBEE_STATUS "|" D_CMND_ZIGBEE_RESET "|" D_CMND_ZIGBEE_SEND "|"
D_CMND_ZIGBEE_PROBE "|" D_CMND_ZIGBEE_READ "|" D_CMND_ZIGBEEZNPRECEIVE "|"
D_CMND_ZIGBEE_FORGET "|" D_CMND_ZIGBEE_SAVE "|" D_CMND_ZIGBEE_NAME "|" D_CMND_ZIGBEE_BIND ;
D_CMND_ZIGBEE_FORGET "|" D_CMND_ZIGBEE_SAVE "|" D_CMND_ZIGBEE_NAME "|" D_CMND_ZIGBEE_BIND "|"
D_CMND_ZIGBEE_PING ;
void (* const ZigbeeCommand[])(void) PROGMEM = {
&CmndZbZNPSend, &CmndZbPermitJoin,
&CmndZbStatus, &CmndZbReset, &CmndZbSend,
&CmndZbProbe, &CmndZbRead, &CmndZbZNPReceive,
&CmndZbForget, &CmndZbSave, &CmndZbName, &CmndZbBind
&CmndZbForget, &CmndZbSave, &CmndZbName, &CmndZbBind,
&CmndZbPing,
};
int32_t ZigbeeProcessInput(class SBuffer &buf) {
@ -344,7 +347,7 @@ void ZigbeeZNPSend(const uint8_t *msg, size_t len) {
ToHex_P(msg, len, hex_char, sizeof(hex_char)));
}
void ZigbeeZCLSend(uint16_t dtsAddr, uint16_t clusterId, uint8_t endpoint, uint8_t cmdId, bool clusterSpecific, const uint8_t *msg, size_t len, bool disableDefResp, uint8_t transacId) {
void ZigbeeZCLSend(uint16_t dtsAddr, uint16_t clusterId, uint8_t endpoint, uint8_t cmdId, bool clusterSpecific, const uint8_t *msg, size_t len, bool needResponse, uint8_t transacId) {
SBuffer buf(25+len);
buf.add8(Z_SREQ | Z_AF); // 24
buf.add8(AF_DATA_REQUEST); // 01
@ -357,7 +360,7 @@ void ZigbeeZCLSend(uint16_t dtsAddr, uint16_t clusterId, uint8_t endpoint, uint8
buf.add8(0x1E); // 1E radius
buf.add8(3 + len);
buf.add8((disableDefResp ? 0x10 : 0x00) | (clusterSpecific ? 0x01 : 0x00)); // Frame Control Field
buf.add8((needResponse ? 0x00 : 0x10) | (clusterSpecific ? 0x01 : 0x00)); // Frame Control Field
buf.add8(transacId); // Transaction Sequance Number
buf.add8(cmdId);
if (len > 0) {
@ -367,61 +370,16 @@ void ZigbeeZCLSend(uint16_t dtsAddr, uint16_t clusterId, uint8_t endpoint, uint8
ZigbeeZNPSend(buf.getBuffer(), buf.len());
}
inline int8_t hexValue(char c) {
if ((c >= '0') && (c <= '9')) {
return c - '0';
}
if ((c >= 'A') && (c <= 'F')) {
return 10 + c - 'A';
}
if ((c >= 'a') && (c <= 'f')) {
return 10 + c - 'a';
}
return -1;
}
uint32_t parseHex(const char **data, size_t max_len = 8) {
uint32_t ret = 0;
for (uint32_t i = 0; i < max_len; i++) {
int8_t v = hexValue(**data);
if (v < 0) { break; } // non hex digit, we stop parsing
ret = (ret << 4) | v;
*data += 1;
}
return ret;
}
void zigbeeZCLSendStr(uint16_t dstAddr, uint8_t endpoint, const char *data) {
uint16_t cluster = 0x0000; // 0x0000 is a valid default value
uint8_t cmd = ZCL_READ_ATTRIBUTES; // default command is READ_ATTRIBUTES
bool clusterSpecific = false;
// Parse 'cmd' in the form "AAAA_BB/CCCCCCCC" or "AAAA!BB/CCCCCCCC"
// where AA is the cluster number, BBBB the command number, CCCC... the payload
// First delimiter is '_' for a global command, or '!' for a cluster specific commanc
cluster = parseHex(&data, 4);
// delimiter
if (('_' == *data) || ('!' == *data)) {
if ('!' == *data) { clusterSpecific = true; }
data++;
} else {
ResponseCmndChar("Wrong delimiter for payload");
return;
}
// parse cmd number
cmd = parseHex(&data, 2);
// move to end of payload
// delimiter is optional
if ('/' == *data) { data++; } // skip delimiter
size_t size = strlen(data);
void zigbeeZCLSendStr(uint16_t dstAddr, uint8_t endpoint, bool clusterSpecific,
uint16_t cluster, uint8_t cmd, const char *param) {
size_t size = param ? strlen(param) : 0;
SBuffer buf((size+2)/2); // actual bytes buffer for data
while (*data) {
uint8_t code = parseHex(&data, 2);
buf.add8(code);
if (param) {
while (*param) {
uint8_t code = parseHex_P(&param, 2);
buf.add8(code);
}
}
if (0 == endpoint) {
@ -430,7 +388,7 @@ void zigbeeZCLSendStr(uint16_t dstAddr, uint8_t endpoint, const char *data) {
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbSend: guessing endpoint 0x%02X"), endpoint);
}
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbSend: dstAddr 0x%04X, cluster 0x%04X, endpoint 0x%02X, cmd 0x%02X, data %s"),
dstAddr, cluster, endpoint, cmd, data);
dstAddr, cluster, endpoint, cmd, param);
if (0 == endpoint) {
AddLog_P2(LOG_LEVEL_INFO, PSTR("ZbSend: unspecified endpoint"));
@ -438,7 +396,7 @@ void zigbeeZCLSendStr(uint16_t dstAddr, uint8_t endpoint, const char *data) {
}
// everything is good, we can send the command
ZigbeeZCLSend(dstAddr, cluster, endpoint, cmd, clusterSpecific, buf.getBuffer(), buf.len());
ZigbeeZCLSend(dstAddr, cluster, endpoint, cmd, clusterSpecific, buf.getBuffer(), buf.len(), false, zigbee_devices.getNextSeqNumber(dstAddr));
// now set the timer, if any, to read back the state later
if (clusterSpecific) {
zigbeeSetCommandTimer(dstAddr, cluster, endpoint);
@ -467,8 +425,12 @@ void CmndZbSend(void) {
static char delim[] = ", "; // delimiters for parameters
uint16_t device = 0xFFFF; // 0xFFFF is broadcast, so considered valid
uint8_t endpoint = 0x00; // 0x00 is invalid for the dst endpoint
// Command elements
uint16_t cluster = 0;
uint8_t cmd = 0;
String cmd_str = ""; // the actual low-level command, either specified or computed
// parse JSON
const JsonVariant &val_device = getCaseInsensitive(json, PSTR("Device"));
if (nullptr != &val_device) {
device = zigbee_devices.parseDeviceParam(val_device.as<char*>());
@ -496,8 +458,9 @@ void CmndZbSend(void) {
String key = it->key;
JsonVariant& value = it->value;
uint32_t x = 0, y = 0, z = 0;
uint16_t cmd_var;
const __FlashStringHelper* tasmota_cmd = zigbeeFindCommand(key.c_str());
const __FlashStringHelper* tasmota_cmd = zigbeeFindCommand(key.c_str(), &cluster, &cmd_var);
if (tasmota_cmd) {
cmd_str = tasmota_cmd;
} else {
@ -533,9 +496,16 @@ void CmndZbSend(void) {
}
}
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbSend: command_template = %s"), cmd_str.c_str());
//AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbSend: command_template = %s"), cmd_str.c_str());
if (0xFF == cmd_var) { // if command number is a variable, replace it with x
cmd = x;
x = y; // and shift other variables
y = z;
} else {
cmd = cmd_var; // or simply copy the cmd number
}
cmd_str = zigbeeCmdAddParams(cmd_str.c_str(), x, y, z); // fill in parameters
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbSend: command_final = %s"), cmd_str.c_str());
//AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbSend: command_final = %s"), cmd_str.c_str());
} else {
// we have zero command, pass through until last error for missing command
}
@ -546,9 +516,9 @@ void CmndZbSend(void) {
// we have an unsupported command type, just ignore it and fallback to missing command
}
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbCmd_actual: ZigbeeZCLSend {\"device\":\"0x%04X\",\"endpoint\":%d,\"send\":\"%s\"}"),
device, endpoint, cmd_str.c_str());
zigbeeZCLSendStr(device, endpoint, cmd_str.c_str());
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbCmd_actual: ZigbeeZCLSend {\"device\":\"0x%04X\",\"endpoint\":%d,\"send\":\"%04X!%02X/%s\"}"),
device, endpoint, cluster, cmd, cmd_str.c_str());
zigbeeZCLSendStr(device, endpoint, true, cluster, cmd, cmd_str.c_str());
} else {
Response_P(PSTR("Missing zigbee 'Send'"));
return;
@ -614,16 +584,28 @@ void CmndZbBind(void) {
// Probe a specific device to get its endpoints and supported clusters
void CmndZbProbe(void) {
CmndZbProbeOrPing(true);
}
void CmndZbProbeOrPing(boolean probe) {
if (zigbee.init_phase) { ResponseCmndChar(D_ZIGBEE_NOT_STARTED); return; }
uint16_t shortaddr = zigbee_devices.parseDeviceParam(XdrvMailbox.data);
if (0x0000 == shortaddr) { ResponseCmndChar("Unknown device"); return; }
if (0xFFFF == shortaddr) { ResponseCmndChar("Invalid parameter"); return; }
// everything is good, we can send the command
Z_SendActiveEpReq(shortaddr);
Z_SendIEEEAddrReq(shortaddr);
if (probe) {
Z_SendActiveEpReq(shortaddr);
}
ResponseCmndDone();
}
// Ping a device, actually a simplified version of ZbProbe
void CmndZbPing(void) {
CmndZbProbeOrPing(false);
}
// Specify, read or erase a Friendly Name
void CmndZbName(void) {
// Syntax is:
@ -728,8 +710,13 @@ void CmndZbRead(void) {
}
}
if (0 == endpoint) { // try to compute the endpoint
endpoint = zigbee_devices.findClusterEndpointIn(device, cluster);
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("ZbSend: guessing endpoint 0x%02X"), endpoint);
}
if ((0 != endpoint) && (attrs_len > 0)) {
ZigbeeZCLSend(device, cluster, endpoint, ZCL_READ_ATTRIBUTES, false, attrs, attrs_len, false /* we do want a response */);
ZigbeeZCLSend(device, cluster, endpoint, ZCL_READ_ATTRIBUTES, false, attrs, attrs_len, true /* we do want a response */, zigbee_devices.getNextSeqNumber(device));
ResponseCmndDone();
} else {
ResponseCmndChar("Missing parameters");

View File

@ -48,7 +48,7 @@ void (* const ShutterCommand[])(void) PROGMEM = {
&CmndShutterSetHalfway, &CmndShutterSetClose, &CmndShutterInvert, &CmndShutterCalibration , &CmndShutterMotorDelay,
&CmndShutterFrequency, &CmndShutterButton, &CmndShutterLock, &CmndShutterEnableEndStopTime};
const char JSON_SHUTTER_POS[] PROGMEM = "\"" D_PRFX_SHUTTER "%d\":{\"Position\":%d,\"Direction\":%d}";
const char JSON_SHUTTER_POS[] PROGMEM = "\"" D_PRFX_SHUTTER "%d\":{\"Position\":%d,\"Direction\":%d,\"Target\":%d}";
const char JSON_SHUTTER_BUTTON[] PROGMEM = "\"" D_PRFX_SHUTTER "%d\":{\"Button%d\":%d}";
#include <Ticker.h>
@ -70,7 +70,7 @@ struct SHUTTER {
int8_t direction[MAX_SHUTTERS]; // 1 == UP , 0 == stop; -1 == down
uint8_t mode = 0; // operation mode definition. see enum type above SHT_OFF_OPEN__OFF_CLOSE, SHT_OFF_ON__OPEN_CLOSE, SHT_PULSE_OPEN__PULSE_CLOSE
int16_t motordelay[MAX_SHUTTERS]; // initial motorstarttime in 0.05sec.
int16_t pwm_frequency; // frequency of PWN for stepper motors
int16_t pwm_frequency[MAX_SHUTTERS]; // frequency of PWN for stepper motors
uint16_t max_pwm_frequency = 1000; // maximum of PWM frequency for openig the shutter. depend on the motor and drivers
uint16_t max_close_pwm_frequency[MAX_SHUTTERS];// maximum of PWM frequency for closeing the shutter. depend on the motor and drivers
uint8_t skip_relay_change; // avoid overrun at endstops
@ -82,17 +82,18 @@ void ShutterLogPos(uint32_t i)
char stemp2[10];
dtostrfd((float)Shutter.time[i] / steps_per_second, 2, stemp2);
AddLog_P2(LOG_LEVEL_INFO, PSTR("SHT: Shutter%d Real %d, Start %d, Stop %d, Dir %d, Delay %d, Rtc %s [s], Freq %d"),
i+1, Shutter.real_position[i], Shutter.start_position[i], Shutter.target_position[i], Shutter.direction[i], Shutter.motordelay[i], stemp2, Shutter.pwm_frequency);
i+1, Shutter.real_position[i], Shutter.start_position[i], Shutter.target_position[i], Shutter.direction[i], Shutter.motordelay[i], stemp2, Shutter.pwm_frequency[i]);
}
void ShutterRtc50mS(void)
{
for (uint32_t i = 0; i < shutters_present; i++) {
for (uint8_t i = 0; i < shutters_present; i++) {
Shutter.time[i]++;
if (Shutter.accelerator[i]) {
Shutter.pwm_frequency += Shutter.accelerator[i];
Shutter.pwm_frequency = tmax(0,tmin(Shutter.direction[i]==1 ? Shutter.max_pwm_frequency : Shutter.max_close_pwm_frequency[i],Shutter.pwm_frequency));
analogWriteFreq(Shutter.pwm_frequency);
//AddLog_P2(LOG_LEVEL_DEBUG, PSTR("SHT: accelerator i=%d -> %d"),i, Shutter.accelerator[i]);
Shutter.pwm_frequency[i] += Shutter.accelerator[i];
Shutter.pwm_frequency[i] = tmax(0,tmin(Shutter.direction[i]==1 ? Shutter.max_pwm_frequency : Shutter.max_close_pwm_frequency[i],Shutter.pwm_frequency[i]));
analogWriteFreq(Shutter.pwm_frequency[i]);
analogWrite(pin[GPIO_PWM1+i], 50);
}
}
@ -102,8 +103,6 @@ void ShutterRtc50mS(void)
int32_t ShutterPercentToRealPosition(uint32_t percent, uint32_t index)
{
if (0 == percent) return 0;
if (100 == percent) return Shutter.open_max[index];
if (Settings.shutter_set50percent[index] != 50) {
return (percent <= 5) ? Settings.shuttercoeff[2][index] * percent : Settings.shuttercoeff[1][index] * percent + Settings.shuttercoeff[0][index];
} else {
@ -138,8 +137,6 @@ int32_t ShutterPercentToRealPosition(uint32_t percent, uint32_t index)
uint8_t ShutterRealToPercentPosition(int32_t realpos, uint32_t index)
{
if (0 >= realpos) return 0;
if (Shutter.open_max[index] <= realpos) return 100;
if (Settings.shutter_set50percent[index] != 50) {
return (Settings.shuttercoeff[2][index] * 5 > realpos) ? SHT_DIV_ROUND(realpos, Settings.shuttercoeff[2][index]) : SHT_DIV_ROUND(realpos-Settings.shuttercoeff[0][index], Settings.shuttercoeff[1][index]);
} else {
@ -203,8 +200,9 @@ void ShutterInit(void)
Shutter.mode = SHT_OFF_ON__OPEN_CLOSE;
if ((pin[GPIO_PWM1+i] < 99) && (pin[GPIO_CNTR1+i] < 99)) {
Shutter.mode = SHT_OFF_ON__OPEN_CLOSE_STEPPER;
Shutter.pwm_frequency = 0;
analogWriteFreq(Shutter.pwm_frequency);
Shutter.pwm_frequency[i] = 0;
Shutter.accelerator[i] = 0;
analogWriteFreq(Shutter.pwm_frequency[i]);
analogWrite(pin[GPIO_PWM1+i], 50);
}
}
@ -256,29 +254,24 @@ void ShutterInit(void)
void ShutterReportPosition(bool always)
{
uint32_t shutter_moving = 0;
Response_P(PSTR("{"));
for (uint32_t i = 0; i < shutters_present; i++) {
//AddLog_P2(LOG_LEVEL_INFO, PSTR("SHT: Shutter %d: Real Pos: %d"), i+1,Shutter.real_position[i]);
uint32_t position = ShutterRealToPercentPosition(Shutter.real_position[i], i);
if (Shutter.direction[i] != 0) {
shutter_moving = 1;
rules_flag.shutter_moving = 1;
ShutterLogPos(i);
}
if (i) { ResponseAppend_P(PSTR(",")); }
ResponseAppend_P(JSON_SHUTTER_POS, i+1, (Settings.shutter_options[i] & 1) ? 100-position : position, Shutter.direction[i]);
ResponseAppend_P(JSON_SHUTTER_POS, i+1, (Settings.shutter_options[i] & 1) ? 100-position : position, Shutter.direction[i], ShutterRealToPercentPosition(Shutter.target_position[i], i));
}
ResponseJsonEnd();
if (always || (1 == shutter_moving)) {
if (always || (rules_flag.shutter_moving)) {
MqttPublishPrefixTopic_P(RESULT_OR_STAT, PSTR(D_PRFX_SHUTTER));
XdrvRulesProcess();
}
if (rules_flag.shutter_moving > shutter_moving) {
rules_flag.shutter_moved = 1;
} else {
rules_flag.shutter_moved = 0;
}
rules_flag.shutter_moving = shutter_moving;
//AddLog_P2(LOG_LEVEL_DEBUG_MORE, PSTR("SHT: rules_flag.shutter_moving: %d, moved %d"), rules_flag.shutter_moving, rules_flag.shutter_moved);
//AddLog_P2(LOG_LEVEL_DEBUG, PSTR("SHT: rules_flag.shutter_moving: %d, moved %d"), rules_flag.shutter_moving, rules_flag.shutter_moved);
}
void ShutterLimitRealAndTargetPositions(uint32_t i) {
@ -304,22 +297,22 @@ void ShutterUpdatePosition(void)
int32_t max_frequency = Shutter.direction[i] == 1 ? Shutter.max_pwm_frequency : Shutter.max_close_pwm_frequency[i];
int32_t max_freq_change_per_sec = Shutter.max_pwm_frequency*steps_per_second / (Shutter.motordelay[i]>0 ? Shutter.motordelay[i] : 1);
int32_t min_runtime_ms = Shutter.pwm_frequency*1000 / max_freq_change_per_sec;
int32_t min_runtime_ms = Shutter.pwm_frequency[i]*1000 / max_freq_change_per_sec;
int32_t velocity = Shutter.direction[i] == 1 ? 100 : Shutter.close_velocity[i];
int32_t minstopway = min_runtime_ms * velocity / 100 * Shutter.pwm_frequency / max_frequency * Shutter.direction[i] ;
int32_t minstopway = min_runtime_ms * velocity / 100 * Shutter.pwm_frequency[i] / max_frequency * Shutter.direction[i] ;
int32_t next_possible_stop = Shutter.real_position[i] + minstopway ;
stop_position_delta =200 * Shutter.pwm_frequency/max_frequency + Shutter.direction[i] * (next_possible_stop - Shutter.target_position[i]);
stop_position_delta =200 * Shutter.pwm_frequency[i]/max_frequency + Shutter.direction[i] * (next_possible_stop - Shutter.target_position[i]);
//Shutter.accelerator[i] = tmin(tmax(max_freq_change_per_sec*(100-(Shutter.direction[i]*(Shutter.target_position[i]-next_possible_stop) ))/2000 , max_freq_change_per_sec*9/200), max_freq_change_per_sec*11/200);
//int32_t act_freq_change = max_freq_change_per_sec/20;
AddLog_P2(LOG_LEVEL_DEBUG_MORE, PSTR("SHT: time: %d, velocity %d, minstopway %d,cur_freq %d, max_frequency %d, act_freq_change %d, min_runtime_ms %d, act.pos %d, next_stop %d, target: %d"),Shutter.time[i],velocity,minstopway,
Shutter.pwm_frequency,max_frequency, Shutter.accelerator[i],min_runtime_ms,Shutter.real_position[i], next_possible_stop,Shutter.target_position[i]);
Shutter.pwm_frequency[i],max_frequency, Shutter.accelerator[i],min_runtime_ms,Shutter.real_position[i], next_possible_stop,Shutter.target_position[i]);
if (Shutter.accelerator[i] < 0 || next_possible_stop * Shutter.direction[i] > Shutter.target_position[i] * Shutter.direction[i] ) {
Shutter.accelerator[i] = - tmin(tmax(max_freq_change_per_sec*(100-(Shutter.direction[i]*(Shutter.target_position[i]-next_possible_stop) ))/2000 , max_freq_change_per_sec*9/200), max_freq_change_per_sec*12/200);
//AddLog_P2(LOG_LEVEL_DEBUG_MORE, PSTR("SHT: Ramp down: acc: %d"), Shutter.accelerator[i]);
} else if ( Shutter.accelerator[i] > 0 && Shutter.pwm_frequency == max_frequency) {
} else if ( Shutter.accelerator[i] > 0 && Shutter.pwm_frequency[i] == max_frequency) {
Shutter.accelerator[i] = 0;
}
} else {
@ -343,13 +336,13 @@ void ShutterUpdatePosition(void)
case SHT_OFF_ON__OPEN_CLOSE_STEPPER:
missing_steps = ((Shutter.target_position[i]-Shutter.start_position[i])*Shutter.direction[i]*Shutter.max_pwm_frequency/2000) - RtcSettings.pulse_counter[i];
//prepare for stop PWM
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("SHT: Remain steps %d, counter %d, freq %d"), missing_steps, RtcSettings.pulse_counter[i] ,Shutter.pwm_frequency);
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("SHT: Remain steps %d, counter %d, freq %d"), missing_steps, RtcSettings.pulse_counter[i] ,Shutter.pwm_frequency[i]);
Shutter.accelerator[i] = 0;
Shutter.pwm_frequency = Shutter.pwm_frequency > 250 ? 250 : Shutter.pwm_frequency;
analogWriteFreq(Shutter.pwm_frequency);
Shutter.pwm_frequency[i] = Shutter.pwm_frequency[i] > 250 ? 250 : Shutter.pwm_frequency[i];
analogWriteFreq(Shutter.pwm_frequency[i]);
analogWrite(pin[GPIO_PWM1+i], 50);
Shutter.pwm_frequency = 0;
analogWriteFreq(Shutter.pwm_frequency);
Shutter.pwm_frequency[i] = 0;
analogWriteFreq(Shutter.pwm_frequency[i]);
while (RtcSettings.pulse_counter[i] < (uint32_t)(Shutter.target_position[i]-Shutter.start_position[i])*Shutter.direction[i]*Shutter.max_pwm_frequency/2000) {
delay(1);
}
@ -391,6 +384,7 @@ void ShutterUpdatePosition(void)
Shutter.direction[i] = 0;
ShutterReportPosition(true);
rules_flag.shutter_moved = 1;
XdrvRulesProcess();
}
}
@ -413,8 +407,8 @@ void ShutterStartInit(uint32_t i, int32_t direction, int32_t target_pos)
Shutter.skip_relay_change = 1;
} else {
if (Shutter.mode == SHT_OFF_ON__OPEN_CLOSE_STEPPER) {
Shutter.pwm_frequency = 0;
analogWriteFreq(Shutter.pwm_frequency);
Shutter.pwm_frequency[i] = 0;
analogWriteFreq(Shutter.pwm_frequency[i]);
analogWrite(pin[GPIO_PWM1+i], 0);
// can be operated without counter, but then not that acurate.
if (pin[GPIO_CNTR1+i] < 99) {
@ -439,10 +433,11 @@ void ShutterWaitForMotorStop(uint32_t i)
if ((SHT_OFF_ON__OPEN_CLOSE == Shutter.mode) || (SHT_OFF_ON__OPEN_CLOSE_STEPPER == Shutter.mode)) {
if (SHT_OFF_ON__OPEN_CLOSE_STEPPER == Shutter.mode) {
//AddLog_P2(LOG_LEVEL_INFO, PSTR("SHT: Frequency change %d"), Shutter.pwm_frequency);
while (Shutter.pwm_frequency > 0) {
Shutter.accelerator[i] = 0;
Shutter.pwm_frequency = tmax(Shutter.pwm_frequency-((Shutter.direction[i] == 1 ? Shutter.max_pwm_frequency : Shutter.max_close_pwm_frequency[i])/(Shutter.motordelay[i]+1)) , 0);
analogWriteFreq(Shutter.pwm_frequency);
while (Shutter.pwm_frequency[i] > 0) {
//AddLog_P2(LOG_LEVEL_DEBUG_MORE, PSTR("SHT: Frequency: %ld, delta: %d"), Shutter.pwm_frequency[i], (int32_t)((Shutter.direction[i] == 1 ? Shutter.max_pwm_frequency : Shutter.max_close_pwm_frequency[i])/(Shutter.motordelay[i]+1)) );
Shutter.pwm_frequency[i] = tmax(Shutter.pwm_frequency[i]-((Shutter.direction[i] == 1 ? Shutter.max_pwm_frequency : Shutter.max_close_pwm_frequency[i])/(Shutter.motordelay[i]+1)) , 0);
//AddLog_P2(LOG_LEVEL_DEBUG_MORE, PSTR("SHT: Frequency: %ld"), Shutter.pwm_frequency[i]);
analogWriteFreq(Shutter.pwm_frequency[i]);
analogWrite(pin[GPIO_PWM1+i], 50);
delay(50);
}
@ -532,7 +527,6 @@ void ShutterButtonHandler(void)
uint8_t shutter_index = Settings.shutter_button[button_index] & 0x03;
uint16_t loops_per_second = 1000 / Settings.button_debounce; // ButtonDebounce (50)
if ((PRESSED == button) && (NOT_PRESSED == Button.last_state[button_index])) {
if (Settings.flag.button_single) { // SetOption13 (0) - Allow only single button press for immediate action
buttonState = SHT_PRESSED_MULTI;
@ -542,9 +536,9 @@ void ShutterButtonHandler(void)
buttonState = SHT_PRESSED_IMMEDIATE;
press_index = 1;