Change analogWrite to ledcWrite, configuration improvements

This commit is contained in:
2026-01-28 15:46:37 +01:00
parent 107339b3d3
commit 564ed20720
11 changed files with 340 additions and 304 deletions

View File

@@ -1,5 +1,4 @@
#pragma once #pragma once
#include <Preferences.h> #include <Preferences.h>
#include <ArduinoJson.h> #include <ArduinoJson.h>
#include <variant> #include <variant>
@@ -45,8 +44,8 @@ static const ConfigDef configdefs[] = {
{"apMask", ConfigType::STRING, String("255.255.255.0")}, {"apMask", ConfigType::STRING, String("255.255.255.0")},
{"stopApTime", ConfigType::SHORT, int16_t(0)}, {"stopApTime", ConfigType::SHORT, int16_t(0)},
{"cpuSpeed", ConfigType::SHORT, int16_t(160)}, {"cpuSpeed", ConfigType::SHORT, int16_t(160)},
{"ledBrightness", ConfigType::BYTE, uint8_t(96)}, {"ledBrightness", ConfigType::SHORT, int16_t(96)},
{"ledRgbBrightness", ConfigType::BYTE, uint8_t(96)}, {"ledRgbBrightness", ConfigType::SHORT, int16_t(96)},
{"tempFormat", ConfigType::CHAR, 'C'}, {"tempFormat", ConfigType::CHAR, 'C'},
{"switchBank", ConfigType::BYTE, uint8_t(0)}, {"switchBank", ConfigType::BYTE, uint8_t(0)},
{"key1", ConfigType::BYTE, uint8_t(1)}, {"key1", ConfigType::BYTE, uint8_t(1)},
@@ -76,6 +75,7 @@ private:
Preferences& prefs; Preferences& prefs;
std::map<String, ConfigValue> values; std::map<String, ConfigValue> values;
std::map<String, const ConfigDef*> defs; std::map<String, const ConfigDef*> defs;
[[noreturn]] void error_abort() const;
public: public:
explicit Config(Preferences& prefs); explicit Config(Preferences& prefs);
void load(); void load();
@@ -92,4 +92,8 @@ public:
float getFloat(const char* key) const; float getFloat(const char* key) const;
char getChar(const char* key) const; char getChar(const char* key) const;
const String& getString(const char* key) const; const String& getString(const char* key) const;
const char* getCString(const char* key) const;
}; };
extern Config config;

4
include/hash.h Normal file
View File

@@ -0,0 +1,4 @@
#pragma once
#include <Arduino.h>
String get_sha256(String payload);

8
include/led.h Normal file
View File

@@ -0,0 +1,8 @@
#pragma once
extern int16_t led_brightness;
extern int16_t rgb_brightness;
void led_init();
void led_test();
void led_blink(uint8_t channel, uint8_t count, int16_t brightness, uint32_t interval_ms);

View File

@@ -1,5 +1,7 @@
#pragma once #pragma once
#include <Arduino.h> #include <Arduino.h>
#include "Nmea2kTwai.h"
#include "N2kDeviceList.h"
#define STRINGIFY_IMPL(x) #x #define STRINGIFY_IMPL(x) #x
#define STRINGIFY(x) STRINGIFY_IMPL(x) #define STRINGIFY(x) STRINGIFY_IMPL(x)
@@ -40,11 +42,23 @@
#define KEY_6 GPIO_NUM_10 // D7 #define KEY_6 GPIO_NUM_10 // D7
#define KEY_DST GPIO_NUM_17 // D8 #define KEY_DST GPIO_NUM_17 // D8
// LEDC / PWM channels
#define LEDC_BUZZER 0
#define LEDC_LED_A 1
#define LEDC_LED_B 2
#define LEDC_LED_C 3
#define LEDC_RGBLED_R 4
#define LEDC_RGBLED_G 5
#define LEDC_RGBLED_B 6
#define LEDC_BASE_FREQ 5000
#define LEDC_RES_BUZZER 8 // 8bit: 0..255
#define LEDC_RES_LED 12 // 12bit: 0..4095
// #define LEDC_TIMER_8_BIT 8
// Buzzer // Buzzer
#define BUZZER GPIO_NUM_43 // TX #define BUZZER GPIO_NUM_43 // TX
#define LEDC_CHANNEL 0
#define LEDC_TIMER_8_BIT 8
#define LEDC_BASE_FREQ 5000
// LEDS // LEDS
#define LED_A GPIO_NUM_3 // A2 #define LED_A GPIO_NUM_3 // A2
@@ -99,13 +113,17 @@ struct ButtonEvent {
ButtonPressType pressType; ButtonPressType pressType;
}; };
extern Nmea2kTwai &NMEA2000;
extern tN2kDeviceList *pN2kDeviceList;
extern char globalmode;
extern uint64_t chipid; extern uint64_t chipid;
extern uint8_t led_brightness; extern int16_t led_brightness;
extern uint8_t rgb_brightness; extern int16_t rgb_brightness;
extern uint8_t keycode[6]; extern uint8_t keycode[6];
extern uint8_t longcode[6]; extern uint8_t longcode[6];
extern float temp; extern float temp;
extern float hum; extern float hum;
String uptime_with_unit();

View File

@@ -1,7 +1,5 @@
#pragma once #pragma once
#include <Arduino.h> #include <Arduino.h>
#include <ESPAsyncWebServer.h> #include <ESPAsyncWebServer.h>
extern AsyncWebServer server; extern AsyncWebServer server;

View File

@@ -1,8 +1,12 @@
#include "config.h" #include "config.h"
#include "esp_rom_uart.h" // for uart wait idle
// Logging // Logging
static const char* TAG = "CFG"; static const char* TAG = "CFG";
Preferences preferences; // persistent storage for configuration
Config config(preferences); // configuration object
Config::Config(Preferences& prefs) Config::Config(Preferences& prefs)
: prefs(prefs) { : prefs(prefs) {
@@ -13,12 +17,19 @@ Config::Config(Preferences& prefs)
} }
[[noreturn]] void Config::error_abort() const {
ESP_LOGD(TAG, "Rebooting in about 2 seconds");
esp_rom_uart_tx_wait_idle(0);
delay(2000); // to have a chance to read
abort();
}
void Config::load() { void Config::load() {
ESP_LOGI(TAG, "Loading configuration"); ESP_LOGD(TAG, "Loading configuration");
prefs.begin(PREF_NAME, true); prefs.begin(PREF_NAME, true);
for (const auto& def : configdefs) { for (const auto& def : configdefs) {
if (prefs.isKey(def.key)) { if (prefs.isKey(def.key)) {
ESP_LOGI(TAG, "Config option '%s' loaded from NVS", def.key); ESP_LOGD(TAG, "Config option '%s' loaded from NVS", def.key);
switch (def.type) { switch (def.type) {
case ConfigType::BYTE: case ConfigType::BYTE:
values[def.key] = (uint8_t)prefs.getUChar(def.key, std::get<uint8_t>(def.defval)); values[def.key] = (uint8_t)prefs.getUChar(def.key, std::get<uint8_t>(def.defval));
@@ -43,7 +54,7 @@ void Config::load() {
break; break;
} }
} else { } else {
ESP_LOGI(TAG, "Using default for '%s'", def.key); ESP_LOGD(TAG, "Using default for '%s'", def.key);
switch (def.type) { switch (def.type) {
case ConfigType::BYTE: case ConfigType::BYTE:
values[def.key] = std::get<uint8_t>(def.defval); values[def.key] = std::get<uint8_t>(def.defval);
@@ -204,36 +215,36 @@ uint8_t Config::getByte(const char* key) const {
auto it = values.find(key); auto it = values.find(key);
if (it == values.end()) { if (it == values.end()) {
ESP_LOGE(TAG, "Missing config key: %s", key); ESP_LOGE(TAG, "Missing config key: %s", key);
abort(); error_abort();
} }
if (auto v = std::get_if<uint8_t>(&it->second)) if (auto v = std::get_if<uint8_t>(&it->second))
return *v; return *v;
ESP_LOGE(TAG, "Type mismatch for key: %s", key); ESP_LOGE(TAG, "Type mismatch for key: %s", key);
abort(); error_abort();
} }
int16_t Config::getShort(const char* key) const { int16_t Config::getShort(const char* key) const {
auto it = values.find(key); auto it = values.find(key);
if (it == values.end()) { if (it == values.end()) {
ESP_LOGE(TAG, "Missing config key: %s", key); ESP_LOGE(TAG, "Missing config key: %s", key);
abort(); error_abort();
} }
if (auto v = std::get_if<int16_t>(&it->second)) if (auto v = std::get_if<int16_t>(&it->second))
return *v; return *v;
ESP_LOGE(TAG, "Type mismatch for key: %s", key); ESP_LOGE(TAG, "Type mismatch for key: %s", key);
abort(); error_abort();
} }
int32_t Config::getInt(const char* key) const { int32_t Config::getInt(const char* key) const {
auto it = values.find(key); auto it = values.find(key);
if (it == values.end()) { if (it == values.end()) {
ESP_LOGE(TAG, "Missing config key: %s", key); ESP_LOGE(TAG, "Missing config key: %s", key);
abort(); error_abort();
} }
if (auto v = std::get_if<int32_t>(&it->second)) if (auto v = std::get_if<int32_t>(&it->second))
return *v; return *v;
ESP_LOGE(TAG, "Type mismatch for key: %s", key); ESP_LOGE(TAG, "Type mismatch for key: %s", key);
abort(); error_abort();
} }
bool Config::getBool(const char* key) const { bool Config::getBool(const char* key) const {
@@ -251,34 +262,38 @@ float Config::getFloat(const char* key) const {
auto it = values.find(key); auto it = values.find(key);
if (it == values.end()) { if (it == values.end()) {
ESP_LOGE(TAG, "Missing config key: %s", key); ESP_LOGE(TAG, "Missing config key: %s", key);
abort(); error_abort();
} }
if (auto v = std::get_if<float>(&it->second)) if (auto v = std::get_if<float>(&it->second))
return *v; return *v;
ESP_LOGE(TAG, "Type mismatch for key: %s", key); ESP_LOGE(TAG, "Type mismatch for key: %s", key);
abort(); error_abort();
} }
char Config::getChar(const char* key) const { char Config::getChar(const char* key) const {
auto it = values.find(key); auto it = values.find(key);
if (it == values.end()) { if (it == values.end()) {
ESP_LOGE(TAG, "Missing config key: %s", key); ESP_LOGE(TAG, "Missing config key: %s", key);
abort(); error_abort();
} }
if (auto v = std::get_if<char>(&it->second)) if (auto v = std::get_if<char>(&it->second))
return *v; return *v;
ESP_LOGE(TAG, "Type mismatch for key: %s", key); ESP_LOGE(TAG, "Type mismatch for key: %s", key);
abort(); error_abort();
} }
const String& Config::getString(const char* key) const { const String& Config::getString(const char* key) const {
auto it = values.find(key); auto it = values.find(key);
if (it == values.end()) { if (it == values.end()) {
ESP_LOGE(TAG, "Missing config key: %s", key); ESP_LOGE(TAG, "Missing config key: %s", key);
abort(); error_abort();
} }
if (auto v = std::get_if<String>(&it->second)) if (auto v = std::get_if<String>(&it->second))
return *v; return *v;
ESP_LOGE(TAG, "Type mismatch for key: %s", key); ESP_LOGE(TAG, "Type mismatch for key: %s", key);
abort(); error_abort();
}
const char* Config::getCString(const char* key) const {
return getString(key).c_str();
} }

32
src/hash.cpp Normal file
View File

@@ -0,0 +1,32 @@
#include "hash.h"
#include "mbedtls/md.h" // for SHA256
String get_sha256(String payload) {
byte shaResult[32];
mbedtls_md_context_t ctx;
mbedtls_md_type_t md_type = MBEDTLS_MD_SHA256;
mbedtls_md_init(&ctx);
mbedtls_md_setup(&ctx, mbedtls_md_info_from_type(md_type), 0);
mbedtls_md_starts(&ctx);
mbedtls_md_update(&ctx, (const unsigned char *) payload.c_str(), payload.length());
mbedtls_md_finish(&ctx, shaResult);
mbedtls_md_free(&ctx);
// convert to hex string
char buffer[sizeof(shaResult)*2 + 1];
const char hexmap[] = "0123456789abcdef";
for (int i = 0; i < sizeof(shaResult); i++) {
buffer[i*2] = hexmap[(shaResult[i] >> 4) & 0x0F];
buffer[i*2+1] = hexmap[shaResult[i] & 0x0F];
}
buffer[sizeof(buffer) - 1] = '\0';
String hash = String(buffer);
Serial.print("SHA256 payload: ");
Serial.print(payload);
Serial.println();
Serial.print("SHA256-Hash: ");
Serial.print(hash);
Serial.println();
return hash;
}

95
src/led.cpp Normal file
View File

@@ -0,0 +1,95 @@
#include "main.h"
#include "led.h"
// Logging
static const char* TAG = "LED";
int16_t led_brightness = 512; // analog pin with ledc: 0 .. 4095
int16_t rgb_brightness = 768;
void led_init() {
// internal user led (red)
digitalWrite(LED_USER, HIGH);
delay(1000);
digitalWrite(LED_USER, LOW);
// LEDC
ledcSetup(LEDC_BUZZER, LEDC_BASE_FREQ, LEDC_RES_BUZZER);
ledcSetup(LEDC_LED_A, LEDC_BASE_FREQ, LEDC_RES_LED);
ledcSetup(LEDC_LED_B, LEDC_BASE_FREQ, LEDC_RES_LED);
ledcSetup(LEDC_LED_C, LEDC_BASE_FREQ, LEDC_RES_LED);
ledcSetup(LEDC_RGBLED_R, LEDC_BASE_FREQ, LEDC_RES_LED);
ledcSetup(LEDC_RGBLED_G, LEDC_BASE_FREQ, LEDC_RES_LED);
ledcSetup(LEDC_RGBLED_B, LEDC_BASE_FREQ, LEDC_RES_LED);
ledcAttachPin(LED_A, LEDC_LED_A);
ledcAttachPin(LED_B, LEDC_LED_B);
ledcAttachPin(LED_C, LEDC_LED_C);
ledcAttachPin(RGBLED_R, LEDC_RGBLED_R);
ledcAttachPin(RGBLED_G, LEDC_RGBLED_G);
ledcAttachPin(RGBLED_B, LEDC_RGBLED_B);
}
void led_test() {
// all led one after another to test functionality
ESP_LOGI(TAG, "LED test started");
// Onbard RGB LED, inverted mode
digitalWrite(LED_IR, LOW);
digitalWrite(LED_IG, HIGH);
digitalWrite(LED_IB, HIGH);
delay(500);
digitalWrite(LED_IR, HIGH);
digitalWrite(LED_IG, LOW);
delay(500);
digitalWrite(LED_IG, HIGH);
digitalWrite(LED_IB, LOW);
delay(500);
digitalWrite(LED_IB, HIGH);
// destination leds
ledcWrite(LEDC_LED_A, 0);
delay(250);
// test every led
ledcWrite(LEDC_LED_A, led_brightness);
ledcWrite(LEDC_LED_B, 0);
ledcWrite(LEDC_LED_C, 0);
delay(500);
ledcWrite(LEDC_LED_A, 0);
ledcWrite(LEDC_LED_B, led_brightness);
delay(500);
ledcWrite(LEDC_LED_B, 0);
ledcWrite(LEDC_LED_C, led_brightness);
delay(500);
ledcWrite(LEDC_LED_C, 0);
// enclosure rgb led (common cathode, so low is off)
ledcWrite(LEDC_RGBLED_R, rgb_brightness);
ledcWrite(LEDC_RGBLED_G, 0);
ledcWrite(LEDC_RGBLED_B, 0);
delay(700);
ledcWrite(LEDC_RGBLED_R, 0);
ledcWrite(LEDC_RGBLED_G, rgb_brightness);
delay(700);
ledcWrite(LEDC_RGBLED_G, 0);
ledcWrite(LEDC_RGBLED_B, rgb_brightness);
delay(700);
ledcWrite(LEDC_RGBLED_B, 0);
ESP_LOGI(TAG, "LED test finished");
}
void led_blink(uint8_t channel, uint8_t count, int16_t brightness, uint32_t interval_ms) {
ledcWrite(channel, 0);
for (uint16_t i = 0; i < count; i++) {
delay(interval_ms);
ledcWrite(channel, brightness);
delay(interval_ms);
ledcWrite(channel, 0);
}
delay(interval_ms);
}

View File

@@ -1,6 +1,8 @@
#include "main.h" #include "main.h"
#include "config.h" #include "config.h"
#include "webserver.h" #include "webserver.h"
#include "led.h"
#include "hash.h"
#include <ArduinoJson.h> #include <ArduinoJson.h>
#include <WiFi.h> #include <WiFi.h>
#include <Wire.h> #include <Wire.h>
@@ -8,14 +10,12 @@
#include <NMEA2000.h> #include <NMEA2000.h>
#include <N2kMsg.h> #include <N2kMsg.h>
#include <N2kMessages.h> #include <N2kMessages.h>
#include "Nmea2kTwai.h"
#include "N2kDeviceList.h"
#include <map> #include <map>
#include "mbedtls/md.h" // for SHA256
#include <esp32/clk.h> // for cpu frequency #include <esp32/clk.h> // for cpu frequency
#include "driver/rtc_io.h" // for wakeup from deep sleep #include "driver/rtc_io.h" // for wakeup from deep sleep
#include "esp_app_format.h" // for custom fw descriptor #include "esp_app_format.h" // for custom fw descriptor
#include "esp_rom_uart.h" // for uart wait idle
// ESP-IDF firmware descriptor // ESP-IDF firmware descriptor
__attribute__((section(".rodata_custom_desc"))) esp_app_desc_t custom_app_desc = { __attribute__((section(".rodata_custom_desc"))) esp_app_desc_t custom_app_desc = {
@@ -31,53 +31,18 @@ __attribute__((section(".rodata_custom_desc"))) esp_app_desc_t custom_app_desc =
{} {}
}; };
String get_sha256(String payload) {
byte shaResult[32];
mbedtls_md_context_t ctx;
mbedtls_md_type_t md_type = MBEDTLS_MD_SHA256;
mbedtls_md_init(&ctx);
mbedtls_md_setup(&ctx, mbedtls_md_info_from_type(md_type), 0);
mbedtls_md_starts(&ctx);
mbedtls_md_update(&ctx, (const unsigned char *) payload.c_str(), payload.length());
mbedtls_md_finish(&ctx, shaResult);
mbedtls_md_free(&ctx);
// convert to hex string
char buffer[sizeof(shaResult)*2 + 1];
const char hexmap[] = "0123456789abcdef";
for (int i = 0; i < sizeof(shaResult); i++) {
buffer[i*2] = hexmap[(shaResult[i] >> 4) & 0x0F];
buffer[i*2+1] = hexmap[shaResult[i] & 0x0F];
}
buffer[sizeof(buffer) - 1] = '\0';
String hash = String(buffer);
Serial.print("SHA256 payload: ");
Serial.print(payload);
Serial.println();
Serial.print("SHA256-Hash: ");
Serial.print(hash);
Serial.println();
return hash;
}
// Logging // Logging
static const char* TAG = "MAIN"; static const char* TAG = "MAIN";
Preferences preferences; // persistent storage for configuration
Config config(preferences); // configuration object
uint64_t chipid = ESP.getEfuseMac(); uint64_t chipid = ESP.getEfuseMac();
const char* wifi_ssid = "OBPKP61"; const char* wifi_ssid = "OBPKP61";
const char* wifi_pass = "keypad61"; const char* wifi_pass = "keypad61";
bool apEnabled = false; bool ap_enabled = false;
// AsyncWebServer server(80);
unsigned long firstStart = 0; unsigned long firstStart = 0;
unsigned long lastSensor = 0; unsigned long lastSensor = 0;
unsigned long lastPrint = 0; unsigned long lastPrint = 0;
unsigned long counter = 0;
bool rgb_r = false; bool rgb_r = false;
bool rgb_g = false; bool rgb_g = false;
@@ -85,13 +50,11 @@ bool rgb_b = false;
int cpuspeed = 240; // MHz int cpuspeed = 240; // MHz
char globalmode = 'K'; // (K)eyboard | (A)utopilot | (L)ogbook RTC_DATA_ATTR char globalmode = 'K'; // (K)eyboard | (A)utopilot | (L)ogbook
char mode = 'N'; // (N)ormal | (C)onfig char mode = 'N'; // (N)ormal | (C)onfig -> do not store for reset!
char ledmode = 'D'; // (D)ay | (N)ight RTC_DATA_ATTR char ledmode = 'D'; // (D)ay | (N)ight
char audiomode = 'E'; // (E)nabled | (D)isabled RTC_DATA_ATTR char audiomode = 'E'; // (E)nabled | (D)isabled
RTC_DATA_ATTR char destination = 'A'; // A | B | C im RTC-Speicher überlebt deep sleep RTC_DATA_ATTR char destination = 'A'; // A | B | C im RTC-Speicher überlebt deep sleep
uint8_t led_brightness = 16; // analog pin: 0 .. 255
uint8_t rgb_brightness = 64;
uint buzzerpower = 50; // TBD make use of this uint buzzerpower = 50; // TBD make use of this
@@ -103,7 +66,7 @@ bool sht_available = false;
float temp = 0.0; float temp = 0.0;
float hum = 0.0; float hum = 0.0;
int nodeid; // NMEA2000 id on bus uint8_t nodeid; // NMEA2000 id on bus
Nmea2kTwai &NMEA2000=*(new Nmea2kTwai(CAN_TX, CAN_RX, CAN_RECOVERY_PERIOD)); Nmea2kTwai &NMEA2000=*(new Nmea2kTwai(CAN_TX, CAN_RX, CAN_RECOVERY_PERIOD));
tN2kDeviceList *pN2kDeviceList; tN2kDeviceList *pN2kDeviceList;
@@ -112,77 +75,6 @@ String processor(const String& var) {
return ""; return "";
} }
String uptime_with_unit() {
int64_t uptime = esp_timer_get_time() / 1000000;
String uptime_unit;
if (uptime < 120) {
uptime_unit = " seconds";
} else {
if (uptime < 2 * 3600) {
uptime /= 60;
uptime_unit = " minutes";
} else if (uptime < 2 * 3600 * 24) {
uptime /= 3600;
uptime_unit = " hours";
} else {
uptime /= 86400;
uptime_unit = " days";
}
}
return String(uptime) + " " + uptime_unit;
}
void ledtest() {
// all led one after another to test functionality
Serial.println("LED test started");
// Onbard RGB LED, inverted mode
digitalWrite(LED_IR, LOW);
digitalWrite(LED_IG, HIGH);
digitalWrite(LED_IB, HIGH);
delay(500);
digitalWrite(LED_IR, HIGH);
digitalWrite(LED_IG, LOW);
delay(500);
digitalWrite(LED_IG, HIGH);
digitalWrite(LED_IB, LOW);
delay(500);
digitalWrite(LED_IB, HIGH);
// destination leds
analogWrite(LED_A, 0);
delay(250);
// test every led
analogWrite(LED_A, led_brightness);
analogWrite(LED_B, 0);
analogWrite(LED_C, 0);
delay(500);
analogWrite(LED_A, 0);
analogWrite(LED_B, led_brightness);
delay(500);
analogWrite(LED_B, 0);
analogWrite(LED_C, led_brightness);
delay(500);
analogWrite(LED_C, 0);
// enclosure rgb led (common cathode, so low is off)
analogWrite(RGBLED_R, rgb_brightness);
analogWrite(RGBLED_G, 0);
analogWrite(RGBLED_B, 0);
delay(700);
analogWrite(RGBLED_R, 0);
analogWrite(RGBLED_G, rgb_brightness);
delay(700);
analogWrite(RGBLED_G, 0);
analogWrite(RGBLED_B, rgb_brightness);
delay(700);
analogWrite(RGBLED_B, 0);
Serial.println("LED test finished");
}
TaskHandle_t ledTaskHandle = NULL; TaskHandle_t ledTaskHandle = NULL;
TaskHandle_t sensorTaskHandle = NULL; TaskHandle_t sensorTaskHandle = NULL;
TaskHandle_t keyTaskHandle = NULL; TaskHandle_t keyTaskHandle = NULL;
@@ -191,17 +83,17 @@ QueueHandle_t ledQueue = NULL;
QueueHandle_t keyQueue = NULL; QueueHandle_t keyQueue = NULL;
void ledTask(void *parameter) { void ledTask(void *parameter) {
Serial.println("Starting LED task"); ESP_LOGI(TAG, "Starting LED task");
for (;;) { for (;;) {
vTaskDelay(5000); vTaskDelay(5000);
analogWrite(RGBLED_G, 10); // a short activity flash ledcWrite(LEDC_RGBLED_G, 160); // a short activity flash
vTaskDelay(20); vTaskDelay(20);
analogWrite(RGBLED_G, 0); ledcWrite(LEDC_RGBLED_G, 0);
} }
} }
void sensorTask(void *parameter) { void sensorTask(void *parameter) {
Serial.println("Starting sensor task"); ESP_LOGI(TAG, "Starting sensor task");
for (;;) { for (;;) {
vTaskDelay(10000); // nothing yet vTaskDelay(10000); // nothing yet
} }
@@ -211,7 +103,7 @@ void keyTask(void *parameter) {
// short key press <= 1s // short key press <= 1s
// medium key press >1s and < 3s // medium key press >1s and < 3s
// long key press >= 3s // long key press >= 3s
Serial.println("Starting keyboard task"); ESP_LOGI(TAG, "Starting keyboard task");
constexpr uint8_t NUM_BUTTONS = 7; constexpr uint8_t NUM_BUTTONS = 7;
constexpr gpio_num_t buttonPins[NUM_BUTTONS] = { constexpr gpio_num_t buttonPins[NUM_BUTTONS] = {
@@ -268,12 +160,12 @@ void keyTask(void *parameter) {
} }
void stopApTimerCallback(TimerHandle_t xTimer) { void stopApTimerCallback(TimerHandle_t xTimer) {
Serial.println("reached AP switchoff time: accesspoint switched off "); ESP_LOGI(TAG, "reached AP switchoff time: accesspoint switched off ");
WiFi.softAPdisconnect(true); WiFi.softAPdisconnect(true);
} }
void cpuFreqTimerCallback(TimerHandle_t xTimer) { void cpuFreqTimerCallback(TimerHandle_t xTimer) {
Serial.println("after 3 minutes: set CPU frequency to 160MHz"); ESP_LOGI(TAG, "after 3 minutes: set CPU frequency to 160MHz");
setCpuFrequencyMhz(cpuspeed); setCpuFrequencyMhz(cpuspeed);
} }
@@ -315,10 +207,10 @@ void setup() {
pinMode(KEY_6, INPUT_PULLUP); pinMode(KEY_6, INPUT_PULLUP);
pinMode(KEY_DST, INPUT_PULLUP); pinMode(KEY_DST, INPUT_PULLUP);
// Early signal system activity // Early signal system activity, red while booting
analogWrite(RGBLED_R, 255); digitalWrite(RGBLED_R, HIGH);
analogWrite(RGBLED_G, 0); digitalWrite(RGBLED_G, LOW);
analogWrite(RGBLED_B, 0); digitalWrite(RGBLED_B, LOW);
// Arduino ESP32 logging // Arduino ESP32 logging
esp_log_level_set("*", ESP_LOG_INFO); esp_log_level_set("*", ESP_LOG_INFO);
@@ -356,9 +248,10 @@ void setup() {
// N2K basics // N2K basics
nodeid = N2K_DEFAULT_NODEID; nodeid = N2K_DEFAULT_NODEID;
ESP_LOGI(TAG, "N2K default node is %d", nodeid); ESP_LOGI(TAG, "N2K default node is %d", nodeid);
preferences.begin(PREF_NAME, false); //preferences.begin(PREF_NAME, false);
nodeid = preferences.getInt("LastNodeId", N2K_DEFAULT_NODEID); //nodeid = preferences.getInt("LastNodeId", N2K_DEFAULT_NODEID);
preferences.end(); //preferences.end();
nodeid = config.getByte("LastNodeId");
ESP_LOGI(TAG, "N2K node id set to %d from preferences", nodeid); ESP_LOGI(TAG, "N2K node id set to %d from preferences", nodeid);
//cpuspeed = preferences.getInt("cpuSpeed", 160); //cpuspeed = preferences.getInt("cpuSpeed", 160);
@@ -392,37 +285,10 @@ void setup() {
IPAddress ap_gateway(ap_addr); IPAddress ap_gateway(ap_addr);
WiFi.softAPConfig(ap_addr, ap_gateway, ap_subnet); WiFi.softAPConfig(ap_addr, ap_gateway, ap_subnet);
apEnabled = true; ap_enabled = true;
// Initialize WebGUI // Initialize WebGUI
webserver_init(); webserver_init();
server.on("/api/devicelist", HTTP_GET, [](AsyncWebServerRequest *request){
// NMEA2000 device list
AsyncResponseStream *response = request->beginResponseStream("application/json");
response->print("[");
bool first = true;
for (int i = 0; i <= 252; i++) {
const tNMEA2000::tDevice *d = pN2kDeviceList->FindDeviceBySource(i);
if (d == nullptr) {
continue;
}
uint64_t NAME = d->GetName();
char hex_name[17];
snprintf(hex_name, sizeof(hex_name), "%08X%08X", (uint32_t)(NAME >> 32), (uint32_t)(NAME & 0xFFFFFFFF));
if (!first) {
response->print(",");
} else {
first = false;
}
// TODO last seen?
response->printf("{\"source\":%d,\"name\":\"%s\",\"manuf\":\"%d\",\"model\":\"%s\"}",
i, hex_name, d->GetManufacturerCode(), d->GetModelID());
}
response->print("]");
request->send(response);
});
// Start HTTP Webserver // Start HTTP Webserver
server.begin(); server.begin();
@@ -486,52 +352,50 @@ void setup() {
// Debug: NMEA2000.EnableForward(true); // Debug: NMEA2000.EnableForward(true);
NMEA2000.Open(); NMEA2000.Open();
// internal user led (red)
digitalWrite(LED_USER, HIGH);
delay(1000); led_init();
digitalWrite(LED_USER, LOW);
// Buzzer // Buzzer
ledcSetup(LEDC_CHANNEL, LEDC_BASE_FREQ, LEDC_TIMER_8_BIT); ledcAttachPin(BUZZER, LEDC_BUZZER);
ledcAttachPin(BUZZER, LEDC_CHANNEL);
// Test tone while booting // Test tone while booting
// Buzzer 12V, 2500Hz +/- 200Hz, 30mA, ca. 90dB // Buzzer 12V, 2500Hz +/- 200Hz, 30mA, ca. 90dB
if (ledcWriteTone(LEDC_CHANNEL, 2300) == 0) { if (ledcWriteTone(LEDC_BUZZER, 2300) == 0) {
Serial.println("Error setting buzzer tone"); Serial.println("Error setting buzzer tone");
} else { } else {
delay(50); delay(50);
ledcWriteTone(LEDC_CHANNEL, 0); // Buzzer off ledcWriteTone(LEDC_BUZZER, 0); // Buzzer off
} }
// Startup sequence: test all led and short beep buzzer // Startup sequence: test all led and short beep buzzer
analogWrite(RGBLED_R, 0); // boot status off digitalWrite(RGBLED_R, LOW); // boot status off
delay(500); delay(500);
ledtest(); led_test();
// select current destination // select current destination
switch (destination) { switch (destination) {
case 'A': case 'A':
analogWrite(LED_A, led_brightness); ledcWrite(LEDC_LED_A, led_brightness);
break; break;
case 'B': case 'B':
analogWrite(LED_B, led_brightness); ledcWrite(LEDC_LED_B, led_brightness);
break; break;
case 'C': case 'C':
analogWrite(LED_C, led_brightness); ledcWrite(LEDC_LED_C, led_brightness);
break; break;
} }
// I²C // I²C
Serial.print("SHT31_LIB_VERSION: "); // Serial.print("SHT31_LIB_VERSION: ");
Serial.println(SHT31_LIB_VERSION); // Serial.println(SHT31_LIB_VERSION);
ESP_LOGI(TAG, "SHT31_LIB_VERSION: %s", SHT31_LIB_VERSION);
Wire.begin(I2C_SDA, I2C_SCL); Wire.begin(I2C_SDA, I2C_SCL);
Wire.setClock(I2C_SPEED); Wire.setClock(I2C_SPEED);
uint16_t stat = sht.readStatus(); uint16_t stat = sht.readStatus();
// stat = ffff anscheinend Fehler // stat = ffff anscheinend Fehler
// = 8010 läuft anscheinend // = 8010 läuft anscheinend
sht_available = (stat == 0x8010); sht_available = (stat == 0x8010);
Serial.print(stat, HEX); ESP_LOGI(TAG, "SHT31 state=0x%X", stat);
Serial.println();
// Additional tests // Additional tests
String passhash = get_sha256("secretTEST"); String passhash = get_sha256("secretTEST");
@@ -553,10 +417,10 @@ void setup() {
ledQueue = xQueueCreate(5, sizeof(uint8_t)); ledQueue = xQueueCreate(5, sizeof(uint8_t));
if (esp_sleep_is_valid_wakeup_gpio(KEY_DST)) { if (esp_sleep_is_valid_wakeup_gpio(KEY_DST)) {
Serial.println("DST-Taste ist als Wakeup-Pin konfiguriert"); ESP_LOGI(TAG, "DST-key configured as wakeup-pin");
esp_sleep_enable_ext0_wakeup(KEY_DST, 0); esp_sleep_enable_ext0_wakeup(KEY_DST, 0);
} else { } else {
Serial.println("Keine Wakeup-Funktion vorhanden! Deep-sleep deaktiviert."); ESP_LOGI(TAG, "No wakeup feature available! Deep-sleep disabled.");
} }
if (cpuspeed < 240) { if (cpuspeed < 240) {
@@ -584,19 +448,19 @@ void setup() {
} }
void shortBeep() { void shortBeep() {
ledcWriteTone(LEDC_CHANNEL, 2500); ledcWriteTone(LEDC_BUZZER, 2500);
delay(15); delay(15);
ledcWriteTone(LEDC_CHANNEL, 0); ledcWriteTone(LEDC_BUZZER, 0);
} }
void atariKeyclick() { void atariKeyclick() {
ledcWriteTone(LEDC_CHANNEL, 3200); ledcWriteTone(LEDC_BUZZER, 3200);
delayMicroseconds(3000); delayMicroseconds(3000);
ledcWriteTone(LEDC_CHANNEL, 0); ledcWriteTone(LEDC_BUZZER, 0);
delayMicroseconds(800); delayMicroseconds(800);
ledcWriteTone(LEDC_CHANNEL, 3200); ledcWriteTone(LEDC_BUZZER, 3200);
delayMicroseconds(2000); delayMicroseconds(2000);
ledcWriteTone(LEDC_CHANNEL, 0); ledcWriteTone(LEDC_BUZZER, 0);
} }
void print_n2k_devicelist() { void print_n2k_devicelist() {
@@ -658,7 +522,7 @@ void send_sensor_temphum(float temp_k, float hum_perc) {
unsigned char instance = 0; unsigned char instance = 0;
tN2kTempSource temp_src = N2kts_OutsideTemperature; // 1=outside, 2=inside tN2kTempSource temp_src = N2kts_OutsideTemperature; // 1=outside, 2=inside
tN2kHumiditySource hum_src = N2khs_OutsideHumidity; // 0=inside, 1=outside tN2kHumiditySource hum_src = N2khs_OutsideHumidity; // 0=inside, 1=outside
Serial.printf("Sending temp=%f K, hum=%f %%\n", temp_k, hum_perc); ESP_LOGI(TAG, "Sending temp=%f K, hum=%f %%", temp_k, hum_perc);
SetN2kPGN130312(N2kMsg, SID, instance, temp_src, temp_k); SetN2kPGN130312(N2kMsg, SID, instance, temp_src, temp_k);
NMEA2000.SendMsg(N2kMsg); NMEA2000.SendMsg(N2kMsg);
SetN2kPGN130313(N2kMsg, SID, instance, hum_src, hum_perc); SetN2kPGN130313(N2kMsg, SID, instance, hum_src, hum_perc);
@@ -670,55 +534,37 @@ void loop() {
ButtonEvent event; ButtonEvent event;
if (xQueueReceive(keyQueue, &event, 0) == pdPASS) { if (xQueueReceive(keyQueue, &event, 0) == pdPASS) {
Serial.print("Button ");
Serial.print(event.buttonId);
Serial.print(" -> ");
switch (event.pressType) {
case ButtonPressType::SHORT:
Serial.println("SHORT");
break;
case ButtonPressType::MEDIUM:
Serial.println("MEDIUM");
break;
case ButtonPressType::LONG:
Serial.println("LONG");
break;
default:
Serial.print("UNBEKANNT: ");
Serial.println(static_cast<uint8_t>(event.pressType));
break;
}
if (event.buttonId == BUTTON_DST) { if (event.buttonId == BUTTON_DST) {
// destination / mode button
if (event.pressType == ButtonPressType::SHORT) { if (event.pressType == ButtonPressType::SHORT) {
if (mode == 'N') { if (mode == 'N') {
// switch destination only in normal mode // switch destination only in normal mode
if (destination == 'A') { if (destination == 'A') {
destination = 'B'; destination = 'B';
analogWrite(LED_A, 0); ledcWrite(LEDC_LED_A, 0);
analogWrite(LED_B, led_brightness); ledcWrite(LEDC_LED_B, led_brightness);
} else if (destination == 'B') { } else if (destination == 'B') {
destination = 'C'; destination = 'C';
analogWrite(LED_B, 0); ledcWrite(LEDC_LED_B, 0);
analogWrite(LED_C, led_brightness); ledcWrite(LEDC_LED_C, led_brightness);
} else { } else {
destination = 'A'; destination = 'A';
analogWrite(LED_C, 0); ledcWrite(LEDC_LED_C, 0);
analogWrite(LED_A, led_brightness); ledcWrite(LEDC_LED_A, led_brightness);
} }
Serial.print("New destination="); ESP_LOGI(TAG, "New destination=%s", destination);
Serial.println(destination);
} }
} else if (event.pressType == ButtonPressType::LONG) { } else if (event.pressType == ButtonPressType::LONG) {
shortBeep(); shortBeep();
// switch config mode // switch config mode
if (mode == 'N') { if (mode == 'N') {
mode = 'C'; mode = 'C';
analogWrite(RGBLED_B, rgb_brightness); // blue status indicator ledcWrite(LEDC_RGBLED_B, rgb_brightness); // blue status indicator
Serial.println("Entering config mode"); ESP_LOGI(TAG, "Entering config mode");
} else { } else {
mode = 'N'; mode = 'N';
analogWrite(RGBLED_B, 0); ledcWrite(LEDC_RGBLED_B, 0);
Serial.println("Leaving config mode"); ESP_LOGI(TAG, "Leaving config mode");
} }
} }
} else { } else {
@@ -742,71 +588,48 @@ void loop() {
switch (event.buttonId) { switch (event.buttonId) {
case BUTTON_1: // switch day/night mode case BUTTON_1: // switch day/night mode
if (ledmode == 'D') { if (ledmode == 'D') {
Serial.println("Night mode enabled"); ESP_LOGI(TAG, "Night mode enabled");
ledmode = 'N'; ledmode = 'N';
} else { } else {
Serial.println("Day mode enabled"); ESP_LOGI(TAG, "Day mode enabled");
ledmode = 'D'; ledmode = 'D';
} }
break; break;
case BUTTON_2: // switch audio on/off case BUTTON_2: // switch audio on/off
if (audiomode == 'E') { if (audiomode == 'E') {
Serial.println("Disabled audio"); ESP_LOGI(TAG, "Disabled audio");
audiomode = 'D'; audiomode = 'D';
} else { } else {
Serial.println("Enabled audio"); ESP_LOGI(TAG, "Enabled audio");
audiomode = 'E'; audiomode = 'E';
} }
break; break;
case BUTTON_3: // switch accesspoint on/off case BUTTON_3: // switch accesspoint on/off
if (apEnabled) { if (ap_enabled) {
Serial.println("Disable Accesspoint"); ESP_LOGI(TAG, "Disable Accesspoint");
WiFi.softAPdisconnect(true); WiFi.softAPdisconnect(true);
apEnabled = false; ap_enabled = false;
} else { } else {
Serial.println("Enable Accesspoint"); Serial.println("Enable Accesspoint");
WiFi.softAP(wifi_ssid, wifi_pass); WiFi.softAP(wifi_ssid, wifi_pass);
apEnabled = true; ap_enabled = true;
} }
break; break;
case BUTTON_4: // reserved case BUTTON_4: // reserved
break; break;
case BUTTON_5: // reset case BUTTON_5: // reset
Serial.println("Device reset"); ESP_LOGI(TAG, "Device reset");
analogWrite(RGBLED_B, 0); esp_rom_uart_tx_wait_idle(0);
delay(500); led_blink(LEDC_RGBLED_G, 3, 4095, 500);
analogWrite(RGBLED_G, 255);
delay(500);
analogWrite(RGBLED_G, 0);
delay(500);
analogWrite(RGBLED_G, 255);
delay(500);
analogWrite(RGBLED_G, 0);
delay(500);
analogWrite(RGBLED_G, 255);
delay(500);
ESP.restart(); ESP.restart();
break; break;
case BUTTON_6: // deep sleep case BUTTON_6: // deep sleep
Serial.println("Going into deep sleep"); ESP_LOGI(TAG, "Going into deep sleep");
Serial.flush(); esp_rom_uart_tx_wait_idle(0);
analogWrite(RGBLED_B, 0); led_blink(LEDC_RGBLED_B, 3, 4095, 500);
delay(500);
analogWrite(RGBLED_B, 255);
delay(500);
analogWrite(RGBLED_B, 0);
delay(500);
analogWrite(RGBLED_B, 255);
delay(500);
analogWrite(RGBLED_B, 0);
delay(500);
analogWrite(RGBLED_B, 255);
delay(500);
rtc_gpio_pullup_en(KEY_DST); rtc_gpio_pullup_en(KEY_DST);
rtc_gpio_pulldown_dis(KEY_DST); rtc_gpio_pulldown_dis(KEY_DST);
esp_deep_sleep_start(); esp_deep_sleep_start();
break; break;
} }
} }
@@ -816,7 +639,7 @@ void loop() {
NMEA2000.loop(); NMEA2000.loop();
NMEA2000.ParseMessages(); NMEA2000.ParseMessages();
if (millis() - lastSensor >= 5000) { if ((millis() - lastSensor >= 5000) and sht_available) {
lastSensor = millis(); lastSensor = millis();
sht.read(); sht.read();
temp = sht.getTemperature(); // °C temp = sht.getTemperature(); // °C
@@ -826,12 +649,5 @@ void loop() {
send_sensor_temphum(temp + 273.15, hum); send_sensor_temphum(temp + 273.15, hum);
} }
// development heartbeat delay(1); // 1ms for FreeRTOS
if (millis() - lastPrint >= 1000) {
lastPrint = millis();
counter++;
Serial.printf("Loop counter: %lu\n", counter);
}
delay(1); // 1ms für freertos
} }

View File

@@ -1,4 +1,5 @@
#include "main.h" #include "main.h"
#include "config.h"
#include "webserver.h" #include "webserver.h"
#include <map> #include <map>
#include <AsyncTCP.h> #include <AsyncTCP.h>
@@ -42,6 +43,26 @@ void send_embedded_file(String name, AsyncWebServerRequest *request)
} }
} }
String uptime_with_unit() {
int64_t uptime = esp_timer_get_time() / 1000000;
String uptime_unit;
if (uptime < 120) {
uptime_unit = " seconds";
} else {
if (uptime < 2 * 3600) {
uptime /= 60;
uptime_unit = " minutes";
} else if (uptime < 2 * 3600 * 24) {
uptime /= 3600;
uptime_unit = " hours";
} else {
uptime /= 86400;
uptime_unit = " days";
}
}
return String(uptime) + " " + uptime_unit;
}
void webserver_init() { void webserver_init() {
// Route for root / web page // Route for root / web page
@@ -76,24 +97,24 @@ void webserver_init() {
server.on("/api/config", HTTP_GET, [](AsyncWebServerRequest *request){ server.on("/api/config", HTTP_GET, [](AsyncWebServerRequest *request){
StaticJsonDocument<512> doc; StaticJsonDocument<512> doc;
doc["systemName"] = "Keypad1"; doc["systemName"] = config.getString("systemName");
doc["systemMode"] = String(config.getChar("systemMode"));
doc["logLevel"] = 0; doc["logLevel"] = 0;
doc["version"] = VERSION; doc["version"] = VERSION;
doc["fwtype"] = "unknown"; doc["fwtype"] = "unknown"; // TODO ?
doc["salt"] = "secret"; doc["salt"] = "secret";
doc["AdminPassword"] = "********"; doc["AdminPassword"] = "********";
doc["useAdminPass"] = false; doc["useAdminPass"] = "false"; //config.getBool("useAdminPass") ? "true" : "false";
doc["apEnable"] = true; doc["apEnable"] = "true";
doc["apIp"] = "192.168.15.1"; doc["apIp"] = config.getString("apIp");
doc["apMask"] = "255.255.255.0"; doc["apMask"] = config.getString("apMask");
doc["apPassword"] = "********"; doc["apPassword"] = "********";
doc["stopApTime"] = 0; doc["stopApTime"] = config.getShort("stopApTime");
doc["cpuSpeed"] = 160; doc["cpuSpeed"] = 160;
doc["tempFormat"] = "C"; doc["tempFormat"] = String(config.getChar("tempFormat"));
doc["ledBrightness"] = led_brightness; doc["ledBrightness"] = led_brightness;
doc["ledRgbBrightness"] = rgb_brightness; doc["ledRgbBrightness"] = rgb_brightness;
doc["tempFormat"] = "C"; doc["switchBank"] = config.getByte("switchBank");
doc["switchBank"] = 0;
doc["key1"] = keycode[BUTTON_1]; doc["key1"] = keycode[BUTTON_1];
doc["key2"] = keycode[BUTTON_2]; doc["key2"] = keycode[BUTTON_2];
doc["key3"] = keycode[BUTTON_3]; doc["key3"] = keycode[BUTTON_3];
@@ -106,7 +127,7 @@ void webserver_init() {
doc["key4long"] = longcode[BUTTON_4]; doc["key4long"] = longcode[BUTTON_4];
doc["key5long"] = longcode[BUTTON_5]; doc["key5long"] = longcode[BUTTON_5];
doc["key6long"] = longcode[BUTTON_6]; doc["key6long"] = longcode[BUTTON_6];
doc["envInterval"] = 5; doc["envInterval"] = 5; // config.getShort("envInterval");
String out; String out;
serializeJson(doc, out); serializeJson(doc, out);
request->send(200, "application/json", out); request->send(200, "application/json", out);
@@ -122,16 +143,12 @@ void webserver_init() {
server.on("/api/status", HTTP_GET, [](AsyncWebServerRequest *request){ server.on("/api/status", HTTP_GET, [](AsyncWebServerRequest *request){
StaticJsonDocument<200> doc; StaticJsonDocument<200> doc;
doc["version"] = VERSION; doc["version"] = VERSION;
int cpu_freq = esp_clk_cpu_freq() / 1000000; int cpu_freq = esp_clk_cpu_freq() / 1000000;
doc["cpuspeed"] = String(cpu_freq) + "MHz"; doc["cpuspeed"] = String(cpu_freq) + "MHz";
char ssid[13]; char ssid[13];
snprintf(ssid, 13, "%04X%08X", (uint16_t)(chipid >> 32), (uint32_t)chipid); snprintf(ssid, 13, "%04X%08X", (uint16_t)(chipid >> 32), (uint32_t)chipid);
doc["chipid"] = String(ssid); doc["chipid"] = String(ssid);
doc["uptime"] = uptime_with_unit(); doc["uptime"] = uptime_with_unit();
doc["heap"]=(long)xPortGetFreeHeapSize(); doc["heap"]=(long)xPortGetFreeHeapSize();
doc["temp"] = String(temp, 1); doc["temp"] = String(temp, 1);
@@ -147,6 +164,9 @@ void webserver_init() {
doc["version"] = VERSION; doc["version"] = VERSION;
doc["build_date"] = BUILD_DATE; doc["build_date"] = BUILD_DATE;
doc["build_time"] = BUILD_TIME; doc["build_time"] = BUILD_TIME;
String out;
serializeJson(doc, out);
request->send(200, "application/json", out);
}); });
server.on("/api/setconfig", HTTP_POST, [](AsyncWebServerRequest *request){ server.on("/api/setconfig", HTTP_POST, [](AsyncWebServerRequest *request){
@@ -187,4 +207,30 @@ void webserver_init() {
}); });
server.on("/api/devicelist", HTTP_GET, [](AsyncWebServerRequest *request){
// NMEA2000 device list
AsyncResponseStream *response = request->beginResponseStream("application/json");
response->print("[");
bool first = true;
for (int i = 0; i <= 252; i++) {
const tNMEA2000::tDevice *d = pN2kDeviceList->FindDeviceBySource(i);
if (d == nullptr) {
continue;
}
uint64_t NAME = d->GetName();
char hex_name[17];
snprintf(hex_name, sizeof(hex_name), "%08X%08X", (uint32_t)(NAME >> 32), (uint32_t)(NAME & 0xFFFFFFFF));
if (!first) {
response->print(",");
} else {
first = false;
}
// TODO last seen?
response->printf("{\"source\":%d,\"name\":\"%s\",\"manuf\":\"%d\",\"model\":\"%s\"}",
i, hex_name, d->GetManufacturerCode(), d->GetModelID());
}
response->print("]");
request->send(response);
});
} }

View File

@@ -25,7 +25,7 @@
"name": "logLevel", "name": "logLevel",
"label": "Log level", "label": "Log level",
"type": "list", "type": "list",
"default": "0", "default": 0,
"list": [ "list": [
{"l":"Off (0)","v":0}, {"l":"Off (0)","v":0},
{"l":"Error (1)","v":1}, {"l":"Error (1)","v":1},