diff --git a/components/bobbycar-protocol b/components/bobbycar-protocol index caaa92e..496e255 160000 --- a/components/bobbycar-protocol +++ b/components/bobbycar-protocol @@ -1 +1 @@ -Subproject commit caaa92eca9141acc42a96b57a62b0e1f086d3ca8 +Subproject commit 496e2556f4858e37df6ae59a84788a34eca862bf diff --git a/components/cxx-ring-buffer b/components/cxx-ring-buffer index c204c20..c9f273b 160000 --- a/components/cxx-ring-buffer +++ b/components/cxx-ring-buffer @@ -1 +1 @@ -Subproject commit c204c208884c08a583f7ded7eb3fa19936761460 +Subproject commit c9f273b51a07b876fa43830e6abb7788587f1d57 diff --git a/components/espasyncota b/components/espasyncota index 7090903..1cc204f 160000 --- a/components/espasyncota +++ b/components/espasyncota @@ -1 +1 @@ -Subproject commit 7090903ce331f3c752f2a9f49ef0f834eb07d59d +Subproject commit 1cc204f1af0925f578445c5a9584bb012fb3f7c8 diff --git a/components/espconfiglib b/components/espconfiglib index fdb4ef6..48ed960 160000 --- a/components/espconfiglib +++ b/components/espconfiglib @@ -1 +1 @@ -Subproject commit fdb4ef6dbfda85e7d41eefaf96f70308108e546e +Subproject commit 48ed9602b8fe155e241353a0f2c7d20f2a6bb5cc diff --git a/components/espcpputils b/components/espcpputils index ed0c502..39a6c64 160000 --- a/components/espcpputils +++ b/components/espcpputils @@ -1 +1 @@ -Subproject commit ed0c50224905dfb3addeb3cec9e6a5e2e3d2d510 +Subproject commit 39a6c64439b29daceb849773bae7b21eb2749e3c diff --git a/components/espwifistack b/components/espwifistack index 118b031..ab236a0 160000 --- a/components/espwifistack +++ b/components/espwifistack @@ -1 +1 @@ -Subproject commit 118b03123e39ba3c6ce9eb30e3a6313c3a6fd0c7 +Subproject commit ab236a065d63f8b6a80f04972d230560bd04c4b3 diff --git a/components/expected b/components/expected index 30ee4ea..ce14a0f 160000 --- a/components/expected +++ b/components/expected @@ -1 +1 @@ -Subproject commit 30ee4ea505463716b03d177d7e65174a697c9eb2 +Subproject commit ce14a0fc6e24b259f1ad413c5432917013e0e207 diff --git a/components/fmt b/components/fmt index d3c349f..7b25dd1 160000 --- a/components/fmt +++ b/components/fmt @@ -1 +1 @@ -Subproject commit d3c349f69de79e0014e2e4fe1c4a1cd7c74983da +Subproject commit 7b25dd172b1b8d851db25436902c76deab098445 diff --git a/dependencies.lock b/dependencies.lock index e794963..12797b8 100644 --- a/dependencies.lock +++ b/dependencies.lock @@ -4,6 +4,6 @@ dependencies: source: type: idf version: 5.0.0 -manifest_hash: eff2ed50019fbc635b22095e8f04bb957b593d3846338eb76bd22bf9803772b2 +manifest_hash: cf95e5bfdc9c844b5103d6aff65aadec10dd0fdc274e1716466d1b549fe1c416 target: esp32 version: 1.0.0 diff --git a/esp-idf b/esp-idf index 3ad5518..243d871 160000 --- a/esp-idf +++ b/esp-idf @@ -1 +1 @@ -Subproject commit 3ad551898dcbfe0bb27b4ee975349328912f2829 +Subproject commit 243d871bd7e09b68dc739cad0896a6cd578d00b9 diff --git a/esp-protocols b/esp-protocols index 6f8ac6c..c7030f4 160000 --- a/esp-protocols +++ b/esp-protocols @@ -1 +1 @@ -Subproject commit 6f8ac6c98d6f5fe4c2e6d4b181a8e88f3b45843b +Subproject commit c7030f402386b2f93012f2c7f4b06d50560126b6 diff --git a/main/accessorhelpers.h b/main/accessorhelpers.h index 85cd0e3..0a56941 100644 --- a/main/accessorhelpers.h +++ b/main/accessorhelpers.h @@ -32,7 +32,7 @@ struct NewSettingsAccessor : public virtual espgui::AccessorInterface T getValue() const override { - return getConfig().value; + return getConfig().value(); } typename espgui::AccessorInterface::setter_result_t setValue(T value) override @@ -51,7 +51,7 @@ struct NewSettingsChronoAdaptorAccessor : public virtual e int32_t getValue() const override { - return getConfig().value.count(); + return getConfig().value().count(); } typename espgui::AccessorInterface::setter_result_t setValue(int32_t value) override @@ -67,7 +67,7 @@ struct NewSettingsChronoAdaptorAccessor : public virt int32_t getValue() const override { - return getConfig().value.count(); + return getConfig().value().count(); } typename espgui::AccessorInterface::setter_result_t setValue(int32_t value) override diff --git a/main/accessors/settingsaccessors.h b/main/accessors/settingsaccessors.h index 2e6176d..5c09b4b 100644 --- a/main/accessors/settingsaccessors.h +++ b/main/accessors/settingsaccessors.h @@ -68,7 +68,7 @@ struct BackRightInvertedAccessor : public RefAccessorSaveSettings { bool & struct WheelDiameterMmAccessor : public NewSettingsAccessor { ConfigWrapper &getConfig() const override { return configs.controllerHardware.wheelDiameter; } }; struct WheelDiameterInchAccessor : public virtual espgui::AccessorInterface { - float getValue() const override { return convertToInch(configs.controllerHardware.wheelDiameter.value); } + float getValue() const override { return convertToInch(configs.controllerHardware.wheelDiameter.value()); } espgui::AccessorInterface::setter_result_t setValue(float value) override { // profileSettings.controllerHardware.wheelDiameter = convertFromInch(value); @@ -80,7 +80,7 @@ struct WheelDiameterInchAccessor : public virtual espgui::AccessorInterface { ConfigWrapper &getConfig() const override { return configs.controllerHardware.numMagnetPoles; } }; struct SwapFrontBackAccessor : public virtual espgui::AccessorInterface { - bool getValue() const override { return configs.controllerHardware.swapFrontBack.value; } + bool getValue() const override { return configs.controllerHardware.swapFrontBack.value(); } setter_result_t setValue(bool value) override { const auto err = configs.write_config(configs.controllerHardware.swapFrontBack, value); @@ -175,7 +175,7 @@ struct LedStripMaxAmpereAccessor : public virtual espgui::AccessorInterface::setter_result_t setValue(float value) override diff --git a/main/battery.cpp b/main/battery.cpp index 8c7305d..55b4b35 100644 --- a/main/battery.cpp +++ b/main/battery.cpp @@ -11,7 +11,7 @@ float getBatteryPercentage(float batVoltage, BatteryCellType cellType) { - const float cellVoltage = batVoltage / configs.battery.cellsSeries.value; + const float cellVoltage = batVoltage / configs.battery.cellsSeries.value(); switch (cellType) { @@ -75,7 +75,7 @@ float getRemainingWattHours() if (const auto avgVoltage = controllers.getAvgVoltage(); avgVoltage) { - return (target_mah / 1000.f) * 3.7 * configs.battery.cellsParallel.value * configs.battery.cellsSeries.value * (getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value)) / 100); + return (target_mah / 1000.f) * 3.7 * configs.battery.cellsParallel.value() * configs.battery.cellsSeries.value() * (getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value())) / 100); } else return 0.; @@ -83,24 +83,24 @@ float getRemainingWattHours() float getPercentageByWh(float wh) { - const float maxWh = (getTarget_mAh() / 1000.f) * 3.7 * configs.battery.cellsParallel.value * configs.battery.cellsSeries.value; + const float maxWh = (getTarget_mAh() / 1000.f) * 3.7 * configs.battery.cellsParallel.value() * configs.battery.cellsSeries.value(); return maxWh / wh; } float getBatteryWattHours() { - return (getTarget_mAh() / 1000.f) * 3.7 * configs.battery.cellsParallel.value * configs.battery.cellsSeries.value; + return (getTarget_mAh() / 1000.f) * 3.7 * configs.battery.cellsParallel.value() * configs.battery.cellsSeries.value(); } float getTarget_mAh() { float target_mah = 2000; //default - if(BatteryCellType(configs.battery.cellType.value) == BatteryCellType::_22P) target_mah = 2200; - if(BatteryCellType(configs.battery.cellType.value) == BatteryCellType::HG2) target_mah = 3000; - if(BatteryCellType(configs.battery.cellType.value) == BatteryCellType::MH1) target_mah = 3200; - if(BatteryCellType(configs.battery.cellType.value) == BatteryCellType::VTC5) target_mah = 2600; - if(BatteryCellType(configs.battery.cellType.value) == BatteryCellType::BAK_25R) target_mah = 2500; - if(BatteryCellType(configs.battery.cellType.value) == BatteryCellType::HE4) target_mah = 2300; + if(BatteryCellType(configs.battery.cellType.value()) == BatteryCellType::_22P) target_mah = 2200; + if(BatteryCellType(configs.battery.cellType.value()) == BatteryCellType::HG2) target_mah = 3000; + if(BatteryCellType(configs.battery.cellType.value()) == BatteryCellType::MH1) target_mah = 3200; + if(BatteryCellType(configs.battery.cellType.value()) == BatteryCellType::VTC5) target_mah = 2600; + if(BatteryCellType(configs.battery.cellType.value()) == BatteryCellType::BAK_25R) target_mah = 2500; + if(BatteryCellType(configs.battery.cellType.value()) == BatteryCellType::HE4) target_mah = 2300; return target_mah; } @@ -108,7 +108,7 @@ std::string getBatteryPercentageString() { if (const auto avgVoltage = controllers.getAvgVoltage(); avgVoltage) { - std::string output = fmt::format("Battery: {:.1f}%", getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value))); + std::string output = fmt::format("Battery: {:.1f}%", getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value()))); return output; } else @@ -128,7 +128,7 @@ std::string getBatteryRemainingWattHoursString() std::string getRemainingRangeString() { - return fmt::format("{:.1f} km", getRemainingWattHours() / configs.battery.watthoursPerKilometer.value); + return fmt::format("{:.1f} km", getRemainingWattHours() / configs.battery.watthoursPerKilometer.value()); } std::string getBatteryDebugString() diff --git a/main/ble_bobby.cpp b/main/ble_bobby.cpp index 636e1d9..dc9c8b9 100644 --- a/main/ble_bobby.cpp +++ b/main/ble_bobby.cpp @@ -55,7 +55,7 @@ void createBle() { ESP_LOGI("BOBBY", "called"); - BLEDevice::init(configs.bluetoothName.value); + BLEDevice::init(configs.bluetoothName.value()); const auto serviceUuid{"0335e46c-f355-4ce6-8076-017de08cee98"}; @@ -97,17 +97,17 @@ void destroyBle() void initBle() { - if (configs.bleSettings.bleEnabled.value) + if (configs.bleSettings.bleEnabled.value()) createBle(); } void handleBle() { - if (!configs.feature.ble.isEnabled.value) + if (!configs.feature.ble.isEnabled.value()) return; - if (configs.bleSettings.bleEnabled.value) + if (configs.bleSettings.bleEnabled.value()) { if (!pServer) createBle(); @@ -237,7 +237,7 @@ void RemoteControlCallbacks::onWrite(NimBLECharacteristic* pCharacteristic) return; } - if (configs.feature.ledstrip.isEnabled.value) + if (configs.feature.ledstrip.isEnabled.value()) { const auto newBlinkAnimation = doc["anim"].as(); if (blinkAnimation != newBlinkAnimation) blinkAnimation = newBlinkAnimation; @@ -287,7 +287,7 @@ void WiFiListCallbacks::onRead(NimBLECharacteristic *pCharacteristic) ESP_LOGI(TAG, "[ble_wifilist] Got request for listing wifi ssids."); for (const auto &wifi : configs.wifi_configs) { - wifiArray.add(wifi.ssid.value); + wifiArray.add(wifi.ssid.value()); } responseDoc["wifi_count"] = configs.wifi_configs.size(); std::string json; diff --git a/main/bobbyblinker.cpp b/main/bobbyblinker.cpp index c9bc71e..3754a77 100644 --- a/main/bobbyblinker.cpp +++ b/main/bobbyblinker.cpp @@ -18,7 +18,7 @@ namespace { void sendState(const std::string& state) { - if (const auto error = espnow::send_espnow_message(fmt::format("{}:{}:{}", state, espchrono::utc_clock::now().time_since_epoch().count(), configs.anhaenger_id.value)); error != ESP_OK) + if (const auto error = espnow::send_espnow_message(fmt::format("{}:{}:{}", state, espchrono::utc_clock::now().time_since_epoch().count(), configs.anhaenger_id.value())); error != ESP_OK) { ESP_LOGE(TAG, "Error sending blinker message: %s", esp_err_to_name(error)); } @@ -33,7 +33,7 @@ namespace bobbyblinker { void handle_blinker() { - if (!configs.espnow.syncBlink.value) + if (!configs.espnow.syncBlink.value()) return; const bool blinker_state = (cpputils::is_in(blinkAnimation, LEDSTRIP_OVERWRITE_BLINKLEFT, LEDSTRIP_OVERWRITE_BLINKRIGHT, LEDSTRIP_OVERWRITE_BLINKBOTH)); @@ -58,7 +58,7 @@ namespace bobbyblinker { blinker_last_time_sent = std::nullopt; sendState("BLINKOFF"); } - if (configs.ledstrip.enableBrakeLights.value && espchrono::ago(*brake_last_time_sent) > 500ms) + if (configs.ledstrip.enableBrakeLights.value() && espchrono::ago(*brake_last_time_sent) > 500ms) { float avgPwm{}; for (const Controller &controller: controllers) { diff --git a/main/bobbybuttons.cpp b/main/bobbybuttons.cpp index c81c64e..715044f 100644 --- a/main/bobbybuttons.cpp +++ b/main/bobbybuttons.cpp @@ -23,37 +23,37 @@ constexpr const char TAG[] = "BUTTONS"; return std::nullopt; using espgui::Button; - if (configs.dpadMappingLeft.value == button) + if (configs.dpadMappingLeft.value() == button) return Button::Left; - if (configs.dpadMappingRight.value == button) + if (configs.dpadMappingRight.value() == button) return Button::Right; - if (configs.dpadMappingUp.value == button) + if (configs.dpadMappingUp.value() == button) return Button::Up; - if (configs.dpadMappingDown.value == button) + if (configs.dpadMappingDown.value() == button) return Button::Down; - if (configs.dpadMappingProfile0.value == button) + if (configs.dpadMappingProfile0.value() == button) return Button(BobbyButton::Profile0); - if (configs.dpadMappingProfile1.value == button) + if (configs.dpadMappingProfile1.value() == button) return Button(BobbyButton::Profile1); - if (configs.dpadMappingProfile2.value == button) + if (configs.dpadMappingProfile2.value() == button) return Button(BobbyButton::Profile2); - if (configs.dpadMappingProfile3.value == button) + if (configs.dpadMappingProfile3.value() == button) return Button(BobbyButton::Profile3); - if (configs.dpadMappingLeft2.value == button) + if (configs.dpadMappingLeft2.value() == button) return Button(BobbyButton::Left2); - if (configs.dpadMappingRight2.value == button) + if (configs.dpadMappingRight2.value() == button) return Button(BobbyButton::Right2); - if (configs.dpadMappingUp2.value == button) + if (configs.dpadMappingUp2.value() == button) return Button(BobbyButton::Up2); - if (configs.dpadMappingDown2.value == button) + if (configs.dpadMappingDown2.value() == button) return Button(BobbyButton::Down2); - if (configs.dpadMappingExtra1.value == button) + if (configs.dpadMappingExtra1.value() == button) return Button(BobbyButton::Extra1); - if (configs.dpadMappingExtra2.value == button) + if (configs.dpadMappingExtra2.value() == button) return Button(BobbyButton::Extra2); - if (configs.dpadMappingExtra3.value == button) + if (configs.dpadMappingExtra3.value() == button) return Button(BobbyButton::Extra3); - if (configs.dpadMappingExtra4.value == button) + if (configs.dpadMappingExtra4.value() == button) return Button(BobbyButton::Extra4); ESP_LOGW(TAG, "unknown raw button %hhu", button); diff --git a/main/bobbyquickactions.cpp b/main/bobbyquickactions.cpp index bcb7e32..832a9c0 100644 --- a/main/bobbyquickactions.cpp +++ b/main/bobbyquickactions.cpp @@ -45,7 +45,7 @@ void handle_bobby_quickaction(espgui::Button button, bool pressed) if (pressed) { - switch (config->value) { + switch (config->value()) { case BobbyQuickActions::BLINK_LEFT: blink_left(); break; @@ -76,7 +76,7 @@ void handle_bobby_quickaction(espgui::Button button, bool pressed) } else { - switch (config->value) { + switch (config->value()) { case BobbyQuickActions::HUPE: bobbyhupe::deactivate_hupe(); break; @@ -88,14 +88,14 @@ void handle_bobby_quickaction(espgui::Button button, bool pressed) void open_garage() { - if (!configs.feature.esp_now.isEnabled.value) + if (!configs.feature.esp_now.isEnabled.value()) return; if (!espnow::espnow_init_allowed()) return; for (const auto &config : configs.wireless_door_configs) { - if (const auto error = espnow::send_espnow_message(fmt::format("BOBBYOPEN:{}:{}", config.doorId.value, config.doorToken.value)); error != ESP_OK) + if (const auto error = espnow::send_espnow_message(fmt::format("BOBBYOPEN:{}:{}", config.doorId.value(), config.doorToken.value())); error != ESP_OK) { ESP_LOGE("BOBBY", "send_espnow_message() failed with: %s", esp_err_to_name(error)); continue; @@ -114,7 +114,7 @@ void action_wifi_scan() void blink_left() { - if (configs.feature.ledstrip.isEnabled.value) + if (configs.feature.ledstrip.isEnabled.value()) { if (blinkAnimation == LEDSTRIP_OVERWRITE_NONE) //transition from off to left { @@ -133,7 +133,7 @@ void blink_left() void blink_right() { - if(configs.feature.ledstrip.isEnabled.value) + if(configs.feature.ledstrip.isEnabled.value()) { if (blinkAnimation == LEDSTRIP_OVERWRITE_NONE) //transition from off to right { @@ -152,7 +152,7 @@ void blink_right() void handle_handbremse() { - if (configs.handbremse.enable.value) + if (configs.handbremse.enable.value()) { using StateWish = handbremse::StateWish; if (handbremse::stateWish == StateWish::brake || handbremse::angezogen) diff --git a/main/buildserver.cpp b/main/buildserver.cpp index 3c9e1c0..e1595d9 100644 --- a/main/buildserver.cpp +++ b/main/buildserver.cpp @@ -22,7 +22,7 @@ namespace buildserver { { uint16_t count = 0; for (const auto &otaServer : configs.otaServers) { - if (!otaServer.url.value.empty()) count++; + if (!otaServer.url.value().empty()) count++; } return count; } @@ -50,7 +50,7 @@ namespace buildserver { return; } - const auto url = fmt::format("{}/otaDescriptor?username={}&branches", server_base_url, configs.otaUsername.value); + const auto url = fmt::format("{}/otaDescriptor?username={}&branches", server_base_url, configs.otaUsername.value()); ESP_LOGD("BOBBY", "requesting data..."); if (const auto result = request->start(url); !result) { @@ -136,9 +136,9 @@ namespace buildserver { if (index < configs.otaServers.size()) { const auto &otaServer = configs.otaServers[index]; - if (!otaServer.url.value.empty()) + if (!otaServer.url.value().empty()) { - return otaServer.url.value; + return otaServer.url.value(); } else { @@ -165,10 +165,10 @@ namespace buildserver { std::string get_descriptor_url(std::string base_url) { - if (configs.otaServerBranch.value.empty()) - return fmt::format("{}/otaDescriptor?username={}", base_url, configs.otaUsername.value); + if (configs.otaServerBranch.value().empty()) + return fmt::format("{}/otaDescriptor?username={}", base_url, configs.otaUsername.value()); else - return fmt::format("{}/otaDescriptor?username={}&branch={}", base_url, configs.otaUsername.value, configs.otaServerBranch.value); + return fmt::format("{}/otaDescriptor?username={}&branch={}", base_url, configs.otaUsername.value(), configs.otaServerBranch.value()); } void parse_response_into_variables(std::string response) @@ -196,8 +196,8 @@ namespace buildserver { index = 0; - url_for_latest = fmt::format("{}{}", configs.otaServerUrl.value, doc["latest"].as()); - url_for_hashes = fmt::format("{}{}", configs.otaServerUrl.value, doc["url"].as()); + url_for_latest = fmt::format("{}{}", configs.otaServerUrl.value(), doc["latest"].as()); + url_for_hashes = fmt::format("{}{}", configs.otaServerUrl.value(), doc["url"].as()); parsing_finished = true; } diff --git a/main/can.cpp b/main/can.cpp index 3cdf4e3..78d7845 100644 --- a/main/can.cpp +++ b/main/can.cpp @@ -203,7 +203,7 @@ bool parseBoardcomputerCanMessage(const twai_message_t &message) bool tryParseCanInput() { twai_message_t message; - const auto timeout = std::chrono::ceil(espchrono::milliseconds32{configs.controllerHardware.canReceiveTimeout.value}).count(); + const auto timeout = std::chrono::ceil(espchrono::milliseconds32{configs.controllerHardware.canReceiveTimeout.value()}).count(); if (const auto result = twai_receive(&message, timeout); result != ESP_OK) { if (result != ESP_ERR_TIMEOUT) @@ -220,8 +220,8 @@ bool tryParseCanInput() return false; } - Controller &front = configs.controllerHardware.swapFrontBack.value ? controllers.back : controllers.front; - Controller &back = configs.controllerHardware.swapFrontBack.value ? controllers.front : controllers.back; + Controller &front = configs.controllerHardware.swapFrontBack.value() ? controllers.back : controllers.front; + Controller &back = configs.controllerHardware.swapFrontBack.value() ? controllers.front : controllers.back; if (parseMotorControllerCanMessage(message, front)) { @@ -274,7 +274,7 @@ void sendCanCommands() std::fill(std::begin(message.data), std::end(message.data), 0); std::memcpy(message.data, &value, sizeof(value)); - const auto timeout = std::chrono::ceil(espchrono::milliseconds32{configs.controllerHardware.canTransmitTimeout.value}).count(); + const auto timeout = std::chrono::ceil(espchrono::milliseconds32{configs.controllerHardware.canTransmitTimeout.value()}).count(); const auto timestamp_before = espchrono::millis_clock::now(); const auto result = twai_transmit(&message, timeout); @@ -308,7 +308,7 @@ void sendCanCommands() if (can_sequential_error_cnt > 3) { can_sequential_error_cnt = 0; - if (configs.canResetOnError.value) + if (configs.canResetOnError.value()) { ESP_LOGW(TAG, "WARNING: Something isn't right, trying to restart can ic..."); if (const auto err = twai_stop(); err != ESP_OK) @@ -316,7 +316,7 @@ void sendCanCommands() ESP_LOGE(TAG, "ERROR: twai_stop() failed with %s", esp_err_to_name(err)); } - if (configs.canUninstallOnReset.value) + if (configs.canUninstallOnReset.value()) { if (const auto err = twai_driver_uninstall(); err != ESP_OK) { ESP_LOGE(TAG, "ERROR: twai_driver_uninstall() failed with %s", esp_err_to_name(err)); @@ -338,13 +338,13 @@ void sendCanCommands() return result; }; - const bool swap = configs.controllerHardware.swapFrontBack.value; + const bool swap = configs.controllerHardware.swapFrontBack.value(); const Controller *front = - (swap ? configs.controllerHardware.sendBackCanCmd.value : configs.controllerHardware.sendFrontCanCmd.value ) ? + (swap ? configs.controllerHardware.sendBackCanCmd.value() : configs.controllerHardware.sendFrontCanCmd.value() ) ? (swap ? &controllers.back : &controllers.front) : nullptr; const Controller *back = - (swap ? configs.controllerHardware.sendFrontCanCmd.value : configs.controllerHardware.sendBackCanCmd.value ) ? + (swap ? configs.controllerHardware.sendFrontCanCmd.value() : configs.controllerHardware.sendBackCanCmd.value() ) ? (swap ? &controllers.front : &controllers.back) : nullptr; diff --git a/main/cloud.cpp b/main/cloud.cpp index 5c5d962..bef80a6 100644 --- a/main/cloud.cpp +++ b/main/cloud.cpp @@ -36,8 +36,8 @@ std::optional lastCloudSend; void initCloud() { - if (configs.cloudSettings.cloudEnabled.value && - !configs.cloudUrl.value.empty()) + if (configs.cloudSettings.cloudEnabled.value() && + !configs.cloudUrl.value().empty()) { createCloud(); if (!cloudClient) @@ -52,19 +52,19 @@ void initCloud() void updateCloud() { - if (!configs.feature.cloud.isEnabled.value) + if (!configs.feature.cloud.isEnabled.value()) return; const auto now = espchrono::millis_clock::now(); - if (!lastCloudCollect || now - *lastCloudCollect >= std::chrono::milliseconds{configs.boardcomputerHardware.timersSettings.cloudCollectRate.value}) + if (!lastCloudCollect || now - *lastCloudCollect >= std::chrono::milliseconds{configs.boardcomputerHardware.timersSettings.cloudCollectRate.value()}) { cloudCollect(); lastCloudCollect = now; } - if (!lastCloudSend || now - *lastCloudSend >= 1000ms/configs.boardcomputerHardware.timersSettings.cloudSendRate.value) + if (!lastCloudSend || now - *lastCloudSend >= 1000ms/configs.boardcomputerHardware.timersSettings.cloudSendRate.value()) { cloudSend(); @@ -168,8 +168,8 @@ void cloudCollect() void cloudSend() { - if (configs.cloudSettings.cloudEnabled.value && - !configs.cloudUrl.value.empty()) + if (configs.cloudSettings.cloudEnabled.value() && + !configs.cloudUrl.value().empty()) { if (!cloudClient) { @@ -201,7 +201,7 @@ void cloudSend() cloudBuffer += ']'; - const auto timeout = std::chrono::ceil(espchrono::milliseconds32{configs.cloudSettings.cloudTransmitTimeout.value}).count(); + const auto timeout = std::chrono::ceil(espchrono::milliseconds32{configs.cloudSettings.cloudTransmitTimeout.value()}).count(); const auto written = cloudClient.send_text(cloudBuffer, timeout); if (written < 0) @@ -234,7 +234,7 @@ void createCloud() lastCreateTry = espchrono::millis_clock::now(); const esp_websocket_client_config_t config = { - .uri = configs.cloudUrl.value.c_str(), + .uri = configs.cloudUrl.value().c_str(), }; cloudClient = espcpputils::websocket_client{&config}; diff --git a/main/controller.cpp b/main/controller.cpp index d66406e..02022a1 100644 --- a/main/controller.cpp +++ b/main/controller.cpp @@ -21,9 +21,9 @@ Controller::Controller( float Controller::getCalibratedVoltage() const { float voltage = feedback.batVoltage; - if (configs.battery.applyCalibration.value) + if (configs.battery.applyCalibration.value()) { - voltage = ((voltage - float(voltageCalib30V.value)) * (20.f / (float(voltageCalib50V.value) - float(voltageCalib30V.value))) + 30.f); + voltage = ((voltage - float(voltageCalib30V.value())) * (20.f / (float(voltageCalib50V.value()) - float(voltageCalib30V.value()))) + 30.f); } else { diff --git a/main/debuginputhandler.cpp b/main/debuginputhandler.cpp index 025f7bf..d82c104 100644 --- a/main/debuginputhandler.cpp +++ b/main/debuginputhandler.cpp @@ -170,6 +170,10 @@ void handleNormalChar(char c) quickactions::blink_right(); } break; + case 'b': + case 'B': + esp_restart(); + break; } } } diff --git a/main/displays/batterygraphdisplay.cpp b/main/displays/batterygraphdisplay.cpp index d2f27f9..aef725d 100644 --- a/main/displays/batterygraphdisplay.cpp +++ b/main/displays/batterygraphdisplay.cpp @@ -28,7 +28,7 @@ std::string BatteryGraphDisplay::text() const { if (const auto avgVoltage = controllers.getAvgVoltage(); avgVoltage) { - return fmt::format("{} ({:.1f}%)", TEXT_BATTERY_GRAPH, getBatteryPercentage(*avgVoltage, configs.battery.cellType.value)); + return fmt::format("{} ({:.1f}%)", TEXT_BATTERY_GRAPH, getBatteryPercentage(*avgVoltage, configs.battery.cellType.value())); } return TEXT_BATTERY_GRAPH; } @@ -42,7 +42,7 @@ void BatteryGraphDisplay::redraw() { if (*avgVoltage == m_lastBatVoltage) return; - const auto cellType = configs.battery.cellType.value; + const auto cellType = configs.battery.cellType.value(); const float onePercent = (tft.width() - 4) / 100.f; const auto percentage = getBatteryPercentage(*avgVoltage, cellType); @@ -75,15 +75,15 @@ void BatteryGraphDisplay::buttonPressed(espgui::Button button) void BatteryGraphDisplay::drawBatteryCurve() { - const auto points = count_curve_points(configs.battery.cellType.value); + const auto points = count_curve_points(configs.battery.cellType.value()); const auto max_height = espgui::tft.height() - 1; const auto max_width = espgui::tft.width() - 4; const uint16_t part = max_width / points; - const auto min_voltage = getMinBatCellVoltage(configs.battery.cellType.value); - const auto max_voltage = getMaxBatCellVoltage(configs.battery.cellType.value); + const auto min_voltage = getMinBatCellVoltage(configs.battery.cellType.value()); + const auto max_voltage = getMaxBatCellVoltage(configs.battery.cellType.value()); for (uint8_t i = 0; points >= i; i++) { // draw lines between point->minVoltage and point->maxVoltage from left to right - if (const auto point = get_point_n_voltages(configs.battery.cellType.value, points - i); point) + if (const auto point = get_point_n_voltages(configs.battery.cellType.value(), points - i); point) { const int x1 = 2 + part * (points - i + 1); const int y1 = float_map(point->minVoltage / 100.f, min_voltage, max_voltage, max_height, TOP_OFFSET); diff --git a/main/displays/calibratevoltagedisplay.cpp b/main/displays/calibratevoltagedisplay.cpp index 7f0bf3d..230ad41 100644 --- a/main/displays/calibratevoltagedisplay.cpp +++ b/main/displays/calibratevoltagedisplay.cpp @@ -72,7 +72,7 @@ class BatteryVoltageCalibrationFront30VText : public virtual espgui::TextInterfa public: std::string text() const override { - return fmt::format("30V Front: {}", convertToFloat(configs.battery.front30VoltCalibration.value)); + return fmt::format("30V Front: {}", convertToFloat(configs.battery.front30VoltCalibration.value())); } }; @@ -81,7 +81,7 @@ class BatteryVoltageCalibrationBack30VText : public virtual espgui::TextInterfac public: std::string text() const override { - return fmt::format("30V Back: {}", convertToFloat(configs.battery.back30VoltCalibration.value)); + return fmt::format("30V Back: {}", convertToFloat(configs.battery.back30VoltCalibration.value())); } }; @@ -90,7 +90,7 @@ class BatteryVoltageCalibrationFront50VText : public virtual espgui::TextInterfa public: std::string text() const override { - return fmt::format("50V Front: {}", convertToFloat(configs.battery.front50VoltCalibration.value)); + return fmt::format("50V Front: {}", convertToFloat(configs.battery.front50VoltCalibration.value())); } }; @@ -99,7 +99,7 @@ class BatteryVoltageCalibrationBack50VText : public virtual espgui::TextInterfac public: std::string text() const override { - return fmt::format("50V Back: {}", convertToFloat(configs.battery.back50VoltCalibration.value)); + return fmt::format("50V Back: {}", convertToFloat(configs.battery.back50VoltCalibration.value())); } }; @@ -108,7 +108,7 @@ class BatteryVoltageCalibratedText : public virtual espgui::TextInterface public: std::string text() const override { - if (configs.battery.applyCalibration.value) + if (configs.battery.applyCalibration.value()) return fmt::format("F{:.2f}V B{:.2f}", controllers.front.getCalibratedVoltage(), controllers.back.getCalibratedVoltage()); else return "Not activated"; diff --git a/main/displays/joystickdebugdisplay.cpp b/main/displays/joystickdebugdisplay.cpp index 28868df..21265ac 100644 --- a/main/displays/joystickdebugdisplay.cpp +++ b/main/displays/joystickdebugdisplay.cpp @@ -40,13 +40,13 @@ void JoystickDebugDisplay::update() m_x = std::nullopt; else { - m_x = map_analog_stick(m_gasMitte, m_gasMin, m_gasMax, configs.deadband.value, *raw_gas); + m_x = map_analog_stick(m_gasMitte, m_gasMin, m_gasMax, configs.deadband.value(), *raw_gas); } if (!raw_brems) m_y = std::nullopt; else - m_y = map_analog_stick(m_bremsMitte, m_bremsMin, m_bremsMax, configs.deadband.value, *raw_brems); + m_y = map_analog_stick(m_bremsMitte, m_bremsMin, m_bremsMax, configs.deadband.value(), *raw_brems); } void JoystickDebugDisplay::redraw() @@ -64,12 +64,12 @@ void JoystickDebugDisplay::redraw() void JoystickDebugDisplay::copyFromSettings() { - m_gasMitte = configs.gasMitte.value; - m_gasMin = configs.gasMin.value; - m_gasMax = configs.gasMax.value; - m_bremsMitte = configs.bremsMitte.value; - m_bremsMin = configs.bremsMin.value; - m_bremsMax = configs.bremsMax.value; + m_gasMitte = configs.gasMitte.value(); + m_gasMin = configs.gasMin.value(); + m_gasMax = configs.gasMax.value(); + m_bremsMitte = configs.bremsMitte.value(); + m_bremsMin = configs.bremsMin.value(); + m_bremsMax = configs.bremsMax.value(); } void JoystickDebugDisplay::buttonPressed(espgui::Button button) diff --git a/main/displays/lockscreen.cpp b/main/displays/lockscreen.cpp index ace5a6b..ae620c5 100644 --- a/main/displays/lockscreen.cpp +++ b/main/displays/lockscreen.cpp @@ -20,7 +20,7 @@ bool isValid1stPin(std::array enteredPin) return std::equal(std::cbegin(enteredPin), std::cend(enteredPin), std::cbegin(configs.lockscreen.pin), std::cend(configs.lockscreen.pin), [](const int8_t digit, const auto &configuredDigit){ - return digit == configuredDigit.value; + return digit == configuredDigit.value(); }); } @@ -29,7 +29,7 @@ bool isValid2ndPin(std::array enteredPin) return std::equal(std::cbegin(enteredPin), std::cend(enteredPin), std::cbegin(configs.lockscreen.pin2), std::cend(configs.lockscreen.pin2), [](const int8_t digit, const auto &configuredDigit){ - return digit == configuredDigit.value; + return digit == configuredDigit.value(); }); } } // namespace @@ -47,7 +47,7 @@ void Lockscreen::start() currentMode = &m_mode; isLocked = true; - if (configs.lockscreen.keepLockedAfterReboot.value && !configs.lockscreen.locked.value) + if (configs.lockscreen.keepLockedAfterReboot.value() && !configs.lockscreen.locked.value()) { configs.write_config(configs.lockscreen.locked, true); } @@ -178,7 +178,7 @@ void Lockscreen::stop() isLocked = false; if (!(!gas || !brems || *gas > 200.f || *brems > 200.f)) { - if (configs.lockscreen.keepLockedAfterReboot.value && configs.lockscreen.locked.value) + if (configs.lockscreen.keepLockedAfterReboot.value() && configs.lockscreen.locked.value()) { configs.write_config(configs.lockscreen.locked, false); } @@ -187,7 +187,7 @@ void Lockscreen::stop() void Lockscreen::buttonPressed(espgui::Button button) { - if (configs.lockscreen.allowPresetSwitch.value || + if (configs.lockscreen.allowPresetSwitch.value() || !cpputils::is_in(button, BobbyButton::Profile0, BobbyButton::Profile1, BobbyButton::Profile2, BobbyButton::Profile3)) Base::buttonPressed(button); diff --git a/main/displays/menus/batterymenu.cpp b/main/displays/menus/batterymenu.cpp index 08bdb2d..40e8f25 100644 --- a/main/displays/menus/batterymenu.cpp +++ b/main/displays/menus/batterymenu.cpp @@ -118,7 +118,7 @@ void BatteryMenu::redraw() if (const auto avgVoltage = controllers.getAvgVoltage(); avgVoltage) { - const auto batPercent = getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value)); + const auto batPercent = getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value())); if (battery::bootBatPercentage) { m_doubleProgressBarBatPercentage.redraw(batPercent, *battery::bootBatPercentage); diff --git a/main/displays/menus/debugmenu.cpp b/main/displays/menus/debugmenu.cpp index 992ddbd..e12639d 100644 --- a/main/displays/menus/debugmenu.cpp +++ b/main/displays/menus/debugmenu.cpp @@ -68,7 +68,7 @@ DebugMenu::DebugMenu() #endif constructMenuItem, PushScreenAction>>(); constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::battery>>>(); - if (configs.feature.udpcloud.isEnabled.value) + if (configs.feature.udpcloud.isEnabled.value()) { constructMenuItem, BobbyCheckbox, CloudDebugEnableAccessor>>(); } diff --git a/main/displays/menus/extrabuttoncalibratemenu.cpp b/main/displays/menus/extrabuttoncalibratemenu.cpp index ff775af..29daf94 100644 --- a/main/displays/menus/extrabuttoncalibratemenu.cpp +++ b/main/displays/menus/extrabuttoncalibratemenu.cpp @@ -255,9 +255,9 @@ void ExtraButtonCalibrateMenu::back() bool ExtraButtonCalibrateMenu::validateNewButton(uint8_t button) { return ( - (button != configs.dpadMappingDown.value) && - (button != configs.dpadMappingUp.value) && - (button != configs.dpadMappingLeft.value) && - (button != configs.dpadMappingRight.value) + (button != configs.dpadMappingDown.value()) && + (button != configs.dpadMappingUp.value()) && + (button != configs.dpadMappingLeft.value()) && + (button != configs.dpadMappingRight.value()) ); } diff --git a/main/displays/menus/featureflagsmenu.cpp b/main/displays/menus/featureflagsmenu.cpp index 6d311a8..97dcc6a 100644 --- a/main/displays/menus/featureflagsmenu.cpp +++ b/main/displays/menus/featureflagsmenu.cpp @@ -45,7 +45,7 @@ public: } else { - if (m_flag.isEnabled.value) + if (m_flag.isEnabled.value()) { return TFT_RED; } @@ -56,13 +56,13 @@ public: void triggered() override { - if (auto result = m_flag.isEnabled.write(configs.nvs_handle_user, !m_flag.isEnabled.value); !result) + if (auto result = m_flag.isEnabled.write(configs.nvs_handle_user, !m_flag.isEnabled.value()); !result) errorOccured(std::move(result).error()); } const MenuItemIcon *icon() const override { - return m_flag.isEnabled.value ? &icons::checked : &icons::unchecked; + return m_flag.isEnabled.value() ? &icons::checked : &icons::unchecked; } private: ConfiguredFeatureFlag &m_flag; diff --git a/main/displays/menus/garagemenu.cpp b/main/displays/menus/garagemenu.cpp index 03a285b..f45ffa4 100644 --- a/main/displays/menus/garagemenu.cpp +++ b/main/displays/menus/garagemenu.cpp @@ -35,10 +35,10 @@ GarageMenu::GarageMenu() for (uint8_t index = 0; index < configs.wireless_door_configs.size(); index++) { const auto &wirelessDoor = configs.wireless_door_configs[index]; - if (wirelessDoor.doorId.value.empty() || wirelessDoor.doorToken.value.empty()) + if (wirelessDoor.doorId.value().empty() || wirelessDoor.doorToken.value().empty()) continue; auto &menuitem = constructMenuItem>(index); - menuitem.setTitle(wirelessDoor.doorId.value); + menuitem.setTitle(wirelessDoor.doorId.value()); } constructMenuItem, PopScreenAction, StaticMenuItemIcon<&espgui::icons::back>>>(); @@ -57,7 +57,7 @@ void GarageMenu::back() namespace { void SendEspNowMessageAction::triggered() { - if (const auto error = espnow::send_espnow_message(fmt::format("BOBBYOPEN:{}:{}", configs.wireless_door_configs[m_index].doorId.value, configs.wireless_door_configs[m_index].doorToken.value)); error != ESP_OK) + if (const auto error = espnow::send_espnow_message(fmt::format("BOBBYOPEN:{}:{}", configs.wireless_door_configs[m_index].doorId.value(), configs.wireless_door_configs[m_index].doorToken.value())); error != ESP_OK) { ESP_LOGE("BOBBY", "send_espnow_message() failed with: %s", esp_err_to_name(error)); return; diff --git a/main/displays/menus/ledstripmenu.cpp b/main/displays/menus/ledstripmenu.cpp index 7a4a671..93ecf35 100644 --- a/main/displays/menus/ledstripmenu.cpp +++ b/main/displays/menus/ledstripmenu.cpp @@ -141,7 +141,7 @@ class LedStripMaxCurrentText : public virtual espgui::TextInterface public: std::string text() const override { - return fmt::format("&sLedstrip max current: &f&2{:.02f}A", configs.ledstrip.maxMilliamps.value / 1000.f); + return fmt::format("&sLedstrip max current: &f&2{:.02f}A", configs.ledstrip.maxMilliamps.value() / 1000.f); } }; } // namespace @@ -170,7 +170,7 @@ LedstripMenu::LedstripMenu() if (!simplified) { constructMenuItem, espgui::PushScreenAction>>(); } constructMenuItem, espgui::PushScreenAction>>(); - if (configs.feature.ota.isEnabled.value) + if (configs.feature.ota.isEnabled.value()) if (!simplified) { constructMenuItem, espgui::PushScreenAction>>(); } constructMenuItem, espgui::PushScreenAction>>(); if (!simplified) { constructMenuItem, espgui::PushScreenAction>>(); } diff --git a/main/displays/menus/mainmenu.cpp b/main/displays/menus/mainmenu.cpp index 067d334..58b1e3d 100644 --- a/main/displays/menus/mainmenu.cpp +++ b/main/displays/menus/mainmenu.cpp @@ -86,7 +86,7 @@ MainMenu::MainMenu() // constructMenuItem>>(); constructMenuItem, PushScreenAction, StaticMenuItemIcon<&espgui::icons::back>>>(); - if (configs.feature.ledstrip.isEnabled.value) + if (configs.feature.ledstrip.isEnabled.value()) { constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::neopixel>>>(); } @@ -97,11 +97,11 @@ MainMenu::MainMenu() constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::settings>>>(); constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::greenpass>>>(); constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::lock>>>(); - if (configs.feature.garage.isEnabled.value && configs.feature.esp_now.isEnabled.value) + if (configs.feature.garage.isEnabled.value() && configs.feature.esp_now.isEnabled.value()) { constructMenuItem, PushScreenAction>>(); } - if (configs.feature.ota.isEnabled.value) + if (configs.feature.ota.isEnabled.value()) constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::update>>>(); constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::graph>>>(); #if defined(FEATURE_CAN) && defined(FEATURE_POWERSUPPLY) diff --git a/main/displays/menus/networksettingsmenu.cpp b/main/displays/menus/networksettingsmenu.cpp index 2c5c59b..0c610d1 100644 --- a/main/displays/menus/networksettingsmenu.cpp +++ b/main/displays/menus/networksettingsmenu.cpp @@ -57,6 +57,6 @@ void NetworkSettingsMenu::back() void NetworkAccessPointQRAction::triggered() { - std::string qr = fmt::format("WIFI:T:{};S:{};P:{};H:;", get_wifi_security_string(configs.wifiApAuthmode.value), configs.wifiApName.value, configs.wifiApKey.value); + std::string qr = fmt::format("WIFI:T:{};S:{};P:{};H:;", get_wifi_security_string(configs.wifiApAuthmode.value()), configs.wifiApName.value(), configs.wifiApKey.value()); espgui::switchScreen>(qr); } diff --git a/main/displays/menus/selectbuildserverbranch.cpp b/main/displays/menus/selectbuildserverbranch.cpp index 7409e5c..3296555 100644 --- a/main/displays/menus/selectbuildserverbranch.cpp +++ b/main/displays/menus/selectbuildserverbranch.cpp @@ -54,7 +54,7 @@ public: namespace { std::string CurrentBranch::text() const { - return configs.otaServerBranch.value.empty() ? "All builds" : configs.otaServerBranch.value; + return configs.otaServerBranch.value().empty() ? "All builds" : configs.otaServerBranch.value(); } std::string BranchMenuItem::text() const @@ -98,7 +98,7 @@ SelectBuildserverBranchMenu::SelectBuildserverBranchMenu() ERR_MESSAGE(TEXT_OTA_NOBUILDSERVERAVAILABLE); // E:No server saved. } - if (configs.otaServerUrl.value.empty()) + if (configs.otaServerUrl.value().empty()) { ERR_MESSAGE(TEXT_OTA_NOBUILDSERVERSELECTED); // E:No server selected. } @@ -110,7 +110,7 @@ SelectBuildserverBranchMenu::SelectBuildserverBranchMenu() #undef ERR_MESSAGE SelectBranch::setup_request(); - SelectBranch::start_descriptor_request(configs.otaServerUrl.value); + SelectBranch::start_descriptor_request(configs.otaServerUrl.value()); } std::string SelectBuildserverBranchMenu::text() const diff --git a/main/displays/menus/selectbuildservermenu.cpp b/main/displays/menus/selectbuildservermenu.cpp index 9a9cf9b..15bd240 100644 --- a/main/displays/menus/selectbuildservermenu.cpp +++ b/main/displays/menus/selectbuildservermenu.cpp @@ -52,8 +52,8 @@ SelectBuildServerMenu::SelectBuildServerMenu() for (const auto &otaServer : configs.otaServers) { - std::string url = otaServer.url.value; - std::string name = (otaServer.name.value.empty()) ? url : otaServer.name.value; + std::string url = otaServer.url.value(); + std::string name = (otaServer.name.value().empty()) ? url : otaServer.name.value(); if (!name.empty()) { diff --git a/main/displays/menus/selectotabuildmenu.cpp b/main/displays/menus/selectotabuildmenu.cpp index 3142a65..f4459e4 100644 --- a/main/displays/menus/selectotabuildmenu.cpp +++ b/main/displays/menus/selectotabuildmenu.cpp @@ -66,7 +66,7 @@ SelectBuildMenu::SelectBuildMenu() MESSAGE(TEXT_OTA_NOBUILDSERVERAVAILABLE); constructMenuItem, PopScreenAction, StaticMenuItemIcon<&espgui::icons::back>>>(); } - else if (configs.otaServerUrl.value.empty()) + else if (configs.otaServerUrl.value().empty()) { MESSAGE(TEXT_OTA_NOBUILDSERVERSELECTED); constructMenuItem, PopScreenAction, StaticMenuItemIcon<&espgui::icons::back>>>(); @@ -81,7 +81,7 @@ SelectBuildMenu::SelectBuildMenu() } else { - std::string serverUrl = configs.otaServerUrl.value; + std::string serverUrl = configs.otaServerUrl.value(); if (serverUrl.substr(serverUrl.length() - 4) == ".bin") { auto &menuitem = constructMenuItem>(); diff --git a/main/displays/menus/settingsmenu.cpp b/main/displays/menus/settingsmenu.cpp index 50f7c82..d559fc4 100644 --- a/main/displays/menus/settingsmenu.cpp +++ b/main/displays/menus/settingsmenu.cpp @@ -96,18 +96,18 @@ SettingsMenu::SettingsMenu() constructMenuItem, PushScreenAction>>(); constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::wifi>>>(); - if (configs.feature.esp_now.isEnabled.value) + if (configs.feature.esp_now.isEnabled.value()) constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::wifi>>>(); #ifdef FEATURE_BLUETOOTH constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::bluetooth>>>(); #endif - if (configs.feature.ble.isEnabled.value) + if (configs.feature.ble.isEnabled.value()) constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::bluetooth>>>(); - if (configs.feature.cloud.isEnabled.value) + if (configs.feature.cloud.isEnabled.value()) constructMenuItem, PushScreenAction>>(); - if (configs.feature.udpcloud.isEnabled.value) + if (configs.feature.udpcloud.isEnabled.value()) constructMenuItem, PushScreenAction>>(); - if (configs.feature.ota.isEnabled.value) + if (configs.feature.ota.isEnabled.value()) constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::update>>>(); constructMenuItem, PushScreenAction, StaticMenuItemIcon<&bobbyicons::time>>>(); if (!simplified) diff --git a/main/displays/menus/statisticsmenu.cpp b/main/displays/menus/statisticsmenu.cpp index 1880f7a..66282da 100644 --- a/main/displays/menus/statisticsmenu.cpp +++ b/main/displays/menus/statisticsmenu.cpp @@ -103,7 +103,7 @@ public: class SavedTotalCentimetersText : public virtual espgui::TextInterface { public: std::string text() const override { - return fmt::format("saved: {}cm", configs.savedStatistics.totalCentimeters.value ); + return fmt::format("saved: {}cm", configs.savedStatistics.totalCentimeters.value() ); } }; diff --git a/main/displays/menus/timesettingsmenu.cpp b/main/displays/menus/timesettingsmenu.cpp index e47c00e..7ce73f9 100644 --- a/main/displays/menus/timesettingsmenu.cpp +++ b/main/displays/menus/timesettingsmenu.cpp @@ -49,7 +49,7 @@ public: #ifdef CONFIG_ESPCHRONO_SUPPORT_DEFAULT_TIMEZONE return fmt::format("local: {}", espchrono::toString(espchrono::toDateTime(espchrono::local_clock::now()))); #else // Mir egal ob die lokalzeit richtig is - return fmt::format("local: {}", espchrono::toString(espchrono::toDateTime(espchrono::utc_clock::now() + configs.timezoneOffset.value))); + return fmt::format("local: {}", espchrono::toString(espchrono::toDateTime(espchrono::utc_clock::now() + configs.timezoneOffset.value()))); #endif } }; @@ -125,7 +125,7 @@ TimeSettingsMenu::TimeSettingsMenu() constructMenuItem, DummyAction>>(); constructMenuItem, SwitchScreenAction>>(); constructMenuItem, SwitchScreenAction>>(); - if (configs.feature.ntp.isEnabled.value) + if (configs.feature.ntp.isEnabled.value()) { constructMenuItem, BobbyCheckbox, TimeServerEnabledAccessor>>(); constructMenuItem, SwitchScreenAction>>(); diff --git a/main/displays/menus/typesafeenumchangemenu.h b/main/displays/menus/typesafeenumchangemenu.h index 58e7208..193d43b 100644 --- a/main/displays/menus/typesafeenumchangemenu.h +++ b/main/displays/menus/typesafeenumchangemenu.h @@ -24,7 +24,7 @@ public: TypesafeEnumCurrentValueMenuItem(ConfigWrapper* config) : m_config{config} {} std::string text() const override { - return toString(m_config->value); + return toString(m_config->value()); } void triggered() override {} diff --git a/main/displays/menus/wifistaconfigsmenu.cpp b/main/displays/menus/wifistaconfigsmenu.cpp index 593e876..b8388c6 100644 --- a/main/displays/menus/wifistaconfigsmenu.cpp +++ b/main/displays/menus/wifistaconfigsmenu.cpp @@ -61,7 +61,7 @@ void WifiStaConfigurationMenuItem::triggered() std::string WifiStaConfigurationMenuItem::text() const { const auto &config = configs.wifi_configs[m_index]; - const auto &ssid = config.ssid.value; + const auto &ssid = config.ssid.value(); bool connected{}; if (!ssid.empty() && wifi_stack::get_sta_status() == wifi_stack::WiFiStaStatus::CONNECTED) diff --git a/main/displays/menus/wifistascanentrymenu.cpp b/main/displays/menus/wifistascanentrymenu.cpp index 4f8ca4c..fa09783 100644 --- a/main/displays/menus/wifistascanentrymenu.cpp +++ b/main/displays/menus/wifistascanentrymenu.cpp @@ -51,7 +51,7 @@ WifiStaScanEntryMenu::WifiStaScanEntryMenu(const wifi_ap_record_t &info) : { const std::string_view ssid{reinterpret_cast(m_info.ssid)}; const bool configured = std::any_of(std::begin(configs.wifi_configs), std::end(configs.wifi_configs), - [&ssid](const WiFiConfig &config){ return cpputils::stringEqualsIgnoreCase(config.ssid.value, ssid); }); + [&ssid](const WiFiConfig &config){ return cpputils::stringEqualsIgnoreCase(config.ssid.value(), ssid); }); constructMenuItem>(fmt::format("&sssid: &f{}{}", configured?"&4":"", richTextEscape(ssid))); constructMenuItem>(fmt::format("&sconfigured: &f{}{}", configured?"&2":"&1", configured?"yes":"no")); @@ -116,7 +116,7 @@ namespace { void SaveNewWifiConfigAction::triggered() { const auto iter = std::find_if(std::begin(configs.wifi_configs), std::end(configs.wifi_configs), - [](const WiFiConfig &config){ return config.ssid.value.empty() && config.key.value.empty(); }); + [](const WiFiConfig &config){ return config.ssid.value().empty() && config.key.value().empty(); }); if (iter == std::end(configs.wifi_configs)) { ESP_LOGE(TAG, "no free wifi config slot found!"); diff --git a/main/displays/menus/wifistascanmenu.cpp b/main/displays/menus/wifistascanmenu.cpp index 5e2bed6..4265ec2 100644 --- a/main/displays/menus/wifistascanmenu.cpp +++ b/main/displays/menus/wifistascanmenu.cpp @@ -138,7 +138,7 @@ std::string WifiStaScanMenuItem::text() const connected = true; const bool configured = std::any_of(std::begin(configs.wifi_configs), std::end(configs.wifi_configs), - [&ssid](const WiFiConfig &config){ return cpputils::stringEqualsIgnoreCase(config.ssid.value, ssid); }); + [&ssid](const WiFiConfig &config){ return cpputils::stringEqualsIgnoreCase(config.ssid.value(), ssid); }); return fmt::format("&s{}{} {}&f{}", rssiToColor(m_info.rssi), diff --git a/main/displays/potiscalibratedisplay.cpp b/main/displays/potiscalibratedisplay.cpp index 4456b46..679f91d 100644 --- a/main/displays/potiscalibratedisplay.cpp +++ b/main/displays/potiscalibratedisplay.cpp @@ -207,7 +207,7 @@ void PotisCalibrateDisplay::buttonPressed(espgui::Button button) case Status::Begin: if (m_bootup) espgui::switchScreen(); - else if (configs.lockscreen.keepLockedAfterReboot.value && configs.lockscreen.locked.value) + else if (configs.lockscreen.keepLockedAfterReboot.value() && configs.lockscreen.locked.value()) { espgui::switchScreen(); configs.write_config(configs.lockscreen.locked, false); @@ -300,13 +300,13 @@ void PotisCalibrateDisplay::buttonPressed(espgui::Button button) void PotisCalibrateDisplay::copyFromSettings() { #ifdef FEATURE_JOYSTICK - m_gasMitte = configs.gasMitte.value; - m_bremsMitte = configs.bremsMitte.value; + m_gasMitte = configs.gasMitte.value(); + m_bremsMitte = configs.bremsMitte.value(); #endif - m_gasMin = configs.gasMin.value; - m_gasMax = configs.gasMax.value; - m_bremsMin = configs.bremsMin.value; - m_bremsMax = configs.bremsMax.value; + m_gasMin = configs.gasMin.value(); + m_gasMax = configs.gasMax.value(); + m_bremsMin = configs.bremsMin.value(); + m_bremsMax = configs.bremsMax.value(); } void PotisCalibrateDisplay::copyToSettings() diff --git a/main/displays/qrcodedebug.cpp b/main/displays/qrcodedebug.cpp index 8450c86..3861478 100644 --- a/main/displays/qrcodedebug.cpp +++ b/main/displays/qrcodedebug.cpp @@ -31,7 +31,7 @@ void QrCodeDebugDisplay::buttonPressed(espgui::Button button) case Button::Right: { uint8_t qrcodeBytes[qrcode_getBufferSize(7)]; - qrcode_initText(&m_qrcode, qrcodeBytes, 7, ECC_MEDIUM, fmt::format("WIFI:T:WPA;S:{};P:{};", configs.wifiApName.value, configs.wifiApKey.value).c_str()); + qrcode_initText(&m_qrcode, qrcodeBytes, 7, ECC_MEDIUM, fmt::format("WIFI:T:WPA;S:{};P:{};", configs.wifiApName.value(), configs.wifiApKey.value()).c_str()); for (uint8_t y = 0; y < m_qrcode.size; y++) { for (uint8_t x = 0; x < m_qrcode.size; x++) { diff --git a/main/displays/statusdisplay.cpp b/main/displays/statusdisplay.cpp index f730caf..d4743ee 100644 --- a/main/displays/statusdisplay.cpp +++ b/main/displays/statusdisplay.cpp @@ -87,12 +87,12 @@ void StatusDisplay::redraw() { static bool handbremse_fill_with_black; - if (configs.handbremse.enable.value && configs.handbremse.visualize.value && handbremse::angezogen) + if (configs.handbremse.enable.value() && configs.handbremse.visualize.value() && handbremse::angezogen) { tft.fillRect(0, tft.height()-6, tft.width(), 6, TFT_RED); handbremse_fill_with_black = true; } - else if (configs.handbremse.enable.value && configs.handbremse.visualize.value && handbremse::stateWish == handbremse::StateWish::brake) + else if (configs.handbremse.enable.value() && configs.handbremse.visualize.value() && handbremse::stateWish == handbremse::StateWish::brake) { tft.fillRect(0, tft.height()-6, tft.width(), 6, TFT_YELLOW); handbremse_fill_with_black = true; @@ -104,10 +104,10 @@ void StatusDisplay::redraw() } } - if(configs.feature.ledstrip.isEnabled.value) + if(configs.feature.ledstrip.isEnabled.value()) { static bool blink_fill_with_black; - if (configs.ledstrip.enableVisualizeBlink.value && (espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms) && (blinkAnimation > 0)) + if (configs.ledstrip.enableVisualizeBlink.value() && (espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms) && (blinkAnimation > 0)) { if (BLINK_LEFT_EXPR) tft.fillRect(0, 0, tft.width() / 2, 6, TFT_YELLOW); @@ -151,9 +151,9 @@ void StatusDisplay::redraw() tft.setTextFont(2); - if (configs.feature.udpcloud.isEnabled.value) + if (configs.feature.udpcloud.isEnabled.value()) { - if(configs.udpCloudSettings.udpCloudEnabled.value && configs.udpCloudSettings.enableCloudDebug.value) + if(configs.udpCloudSettings.udpCloudEnabled.value() && configs.udpCloudSettings.enableCloudDebug.value()) { tft.fillRect(125, 258, 8, 8, (visualSendUdpPacket) ? TFT_DARKGREY : TFT_BLACK); } @@ -218,7 +218,7 @@ clearIp: } m_labelMode.redraw(currentMode->displayName()); - m_labelName.redraw(configs.wifiApName.value); + m_labelName.redraw(configs.wifiApName.value()); const auto profile = settingsPersister.currentlyOpenProfileIndex(); m_labelProfile.redraw(profile ? std::to_string(*profile) : "-"); } diff --git a/main/displays/updatedisplay.cpp b/main/displays/updatedisplay.cpp index db12db2..981a119 100644 --- a/main/displays/updatedisplay.cpp +++ b/main/displays/updatedisplay.cpp @@ -108,7 +108,7 @@ void UpdateDisplay::buttonPressed(espgui::Button button) espgui::popScreen(); break; case Button::Right: - if (const auto result = triggerOta(configs.otaUrl.value); !result) + if (const auto result = triggerOta(configs.otaUrl.value()); !result) ESP_LOGE("BOBBY", "triggerOta() failed with %.*s", result.error().size(), result.error().data()); break; default:; diff --git a/main/dnsannounce.cpp b/main/dnsannounce.cpp index 0525d3f..3c60513 100644 --- a/main/dnsannounce.cpp +++ b/main/dnsannounce.cpp @@ -24,7 +24,7 @@ void init_dns_announce() void handle_dns_announce() { - if (!configs.feature.dnsannounce.isEnabled.value || !configs.dns_announce_enabled.value) + if (!configs.feature.dnsannounce.isEnabled.value() || !configs.dns_announce_enabled.value()) return; if (wifi_stack::get_sta_status() != wifi_stack::WiFiStaStatus::CONNECTED) @@ -50,7 +50,7 @@ void handle_dns_announce() { dns_lastIpAddress_v4 = curIpAddress; ip_addr_t tmpIpResolved; - std::string toLookup = fmt::format("{}__{}.{}.announce.bobbycar.cloud", randDNSName, curIpAddress, configs.otaUsername.value); + std::string toLookup = fmt::format("{}__{}.{}.announce.bobbycar.cloud", randDNSName, curIpAddress, configs.otaUsername.value()); ESP_LOGI("BOBBY", "Trying to look up %s", toLookup.c_str()); if (const auto err = dns_gethostbyname(toLookup.c_str(), &tmpIpResolved, NULL, NULL); err != ERR_OK && err != ERR_INPROGRESS) { @@ -76,7 +76,7 @@ void handle_dns_announce() { dns_lastIpAddress_v6 = curIpV6Address; ip_addr_t tmpIpResolved; - std::string toLookup = fmt::format("{}__{}.{}.announce6.bobbycar.cloud", randDNSName, curIpV6Address, configs.otaUsername.value); + std::string toLookup = fmt::format("{}__{}.{}.announce6.bobbycar.cloud", randDNSName, curIpV6Address, configs.otaUsername.value()); ESP_LOGI("BOBBY", "Trying to look up %s", toLookup.c_str()); if (const auto err = dns_gethostbyname(toLookup.c_str(), &tmpIpResolved, NULL, NULL); err != ERR_OK && err != ERR_INPROGRESS) { @@ -96,7 +96,7 @@ void handle_dns_announce() dns_lastIpAddress_v6_global = curIpV6Address; std::replace(curIpV6Address.begin(), curIpV6Address.end(), ':', '-'); ip_addr_t tmpIpResolved; - std::string toLookup = fmt::format("{}global__{}.{}.announce6.bobbycar.cloud", randDNSName, curIpV6Address, configs.otaUsername.value); + std::string toLookup = fmt::format("{}global__{}.{}.announce6.bobbycar.cloud", randDNSName, curIpV6Address, configs.otaUsername.value()); ESP_LOGI("BOBBY", "Trying to look up %s", toLookup.c_str()); if (const auto err = dns_gethostbyname(toLookup.c_str(), &tmpIpResolved, NULL, NULL); err != ERR_OK && err != ERR_INPROGRESS) { diff --git a/main/dpad5wire_2out.cpp b/main/dpad5wire_2out.cpp index 9532d73..350b082 100644 --- a/main/dpad5wire_2out.cpp +++ b/main/dpad5wire_2out.cpp @@ -52,8 +52,8 @@ std::array Helper::read() pinMode(IN2, INPUT_PULLUP); pinMode(IN3, INPUT_PULLUP); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -68,8 +68,8 @@ std::array Helper::read() pinMode(IN2, INPUT_PULLDOWN); pinMode(IN3, INPUT_PULLDOWN); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -87,8 +87,8 @@ std::array Helper::read() pinMode(IN2, INPUT_PULLUP); pinMode(IN3, INPUT_PULLUP); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -103,8 +103,8 @@ std::array Helper::read() pinMode(IN2, INPUT_PULLDOWN); pinMode(IN3, INPUT_PULLDOWN); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -139,7 +139,7 @@ void update() const auto now = espchrono::millis_clock::now(); - const std::chrono::milliseconds dpadDebounce{configs.dpadDebounce.value}; + const std::chrono::milliseconds dpadDebounce{configs.dpadDebounce.value()}; for (auto i = 0; i < 12; i++) if (lastState[i] != newState[i] && now - debounce[i] > dpadDebounce) diff --git a/main/dpad6wire.cpp b/main/dpad6wire.cpp index 366f018..a52dfdd 100644 --- a/main/dpad6wire.cpp +++ b/main/dpad6wire.cpp @@ -53,8 +53,8 @@ std::array Helper::read() pinMode(IN4, INPUT_PULLUP); pinMode(IN5, INPUT_PULLUP); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -73,8 +73,8 @@ std::array Helper::read() pinMode(IN4, INPUT_PULLDOWN); pinMode(IN5, INPUT_PULLDOWN); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -85,7 +85,7 @@ std::array Helper::read() result[7] = digitalRead(IN4); result[9] = digitalRead(IN5); - if (configs.feature.gschissene_diode.isEnabled.value && (result[8] && result[9])) + if (configs.feature.gschissene_diode.isEnabled.value() && (result[8] && result[9])) { result[9] = 0; } @@ -121,7 +121,7 @@ void update() const auto now = espchrono::millis_clock::now(); - const std::chrono::milliseconds dpadDebounce{configs.dpadDebounce.value}; + const std::chrono::milliseconds dpadDebounce{configs.dpadDebounce.value()}; for (auto i = 0; i < 10; i++) if (lastState[i] != newState[i] && now - debounce[i] > dpadDebounce) diff --git a/main/dpad_boardcomputer_v2.cpp b/main/dpad_boardcomputer_v2.cpp index fafbd68..ea56ea2 100644 --- a/main/dpad_boardcomputer_v2.cpp +++ b/main/dpad_boardcomputer_v2.cpp @@ -56,8 +56,8 @@ std::array Helper::read() pinMode(IN3, INPUT_PULLUP); pinMode(IN4, INPUT_PULLUP); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -74,8 +74,8 @@ std::array Helper::read() pinMode(IN3, INPUT_PULLDOWN); pinMode(IN4, INPUT_PULLDOWN); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -96,8 +96,8 @@ std::array Helper::read() pinMode(IN3, INPUT_PULLUP); pinMode(IN4, INPUT_PULLUP); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -114,8 +114,8 @@ std::array Helper::read() pinMode(IN3, INPUT_PULLDOWN); pinMode(IN4, INPUT_PULLDOWN); - if (configs.buttonReadDelay.value != 0) { - delayMicroseconds(configs.buttonReadDelay.value); + if (configs.buttonReadDelay.value() != 0) { + delayMicroseconds(configs.buttonReadDelay.value()); } else { vPortYield(); } @@ -177,7 +177,7 @@ void update() const auto now = espchrono::millis_clock::now(); - const std::chrono::milliseconds dpadDebounce{configs.dpadDebounce.value}; + const std::chrono::milliseconds dpadDebounce{configs.dpadDebounce.value()}; for (auto i = 0; i < newState.size(); i++) if (lastState[i] != newState[i] && now - debounce[i] > dpadDebounce) diff --git a/main/drivingstatistics.cpp b/main/drivingstatistics.cpp index 9a1b59d..e7e6b63 100644 --- a/main/drivingstatistics.cpp +++ b/main/drivingstatistics.cpp @@ -74,10 +74,10 @@ void calculateStatistics() { static bool saveTotal = false; - if ((configs.savedStatistics.totalCentimeters.value / 100.f) > drivingStatistics.totalMeters) + if ((configs.savedStatistics.totalCentimeters.value() / 100.f) > drivingStatistics.totalMeters) { - drivingStatistics.totalMeters = configs.savedStatistics.totalCentimeters.value / 100.f; - drivingStatistics.last_cm_written = configs.savedStatistics.totalCentimeters.value; + drivingStatistics.totalMeters = configs.savedStatistics.totalCentimeters.value() / 100.f; + drivingStatistics.last_cm_written = configs.savedStatistics.totalCentimeters.value(); } static auto last_km_calculation = espchrono::millis_clock::now(); diff --git a/main/espnowfunctions.cpp b/main/espnowfunctions.cpp index 93e7ed8..3e625d7 100644 --- a/main/espnowfunctions.cpp +++ b/main/espnowfunctions.cpp @@ -33,13 +33,13 @@ bool espnow_init_allowed() const auto wifi_mode = wifi_stack::get_wifi_mode(); return ( - (configs.espnow.syncBlink.value || configs.espnow.syncTime.value || configs.espnow.syncTimeWithOthers.value) + (configs.espnow.syncBlink.value() || configs.espnow.syncTime.value() || configs.espnow.syncTimeWithOthers.value()) && ( - (configs.wifiApEnabled.value && wifi_stack::get_wifi_mode() == WIFI_MODE_AP) + (configs.wifiApEnabled.value() && wifi_stack::get_wifi_mode() == WIFI_MODE_AP) || ( - configs.wifiStaEnabled.value + configs.wifiStaEnabled.value() && wifi_stack::get_sta_status() != wifi_stack::WiFiStaStatus::NO_SHIELD && @@ -83,7 +83,7 @@ void initESPNow() if (initialized < 1) { - if (!configs.wifiApEnabled.value && (!configs.wifiStaEnabled.value && wifi_stack::get_sta_status() == wifi_stack::WiFiStaStatus::NO_SHIELD) || (wifi_stack::get_wifi_mode() != wifi_mode_t::WIFI_MODE_STA && wifi_stack::get_wifi_mode() != wifi_mode_t::WIFI_MODE_AP && wifi_stack::get_wifi_mode() != wifi_mode_t::WIFI_MODE_APSTA) && (configs.espnow.syncBlink.value || configs.espnow.syncTime.value || configs.espnow.syncTimeWithOthers.value)) + if (!configs.wifiApEnabled.value() && (!configs.wifiStaEnabled.value() && wifi_stack::get_sta_status() == wifi_stack::WiFiStaStatus::NO_SHIELD) || (wifi_stack::get_wifi_mode() != wifi_mode_t::WIFI_MODE_STA && wifi_stack::get_wifi_mode() != wifi_mode_t::WIFI_MODE_AP && wifi_stack::get_wifi_mode() != wifi_mode_t::WIFI_MODE_APSTA) && (configs.espnow.syncBlink.value() || configs.espnow.syncTime.value() || configs.espnow.syncTimeWithOthers.value())) { ESP_LOGW(TAG, "cannot execute esp_now_init(): tcp stack is down."); return; @@ -121,9 +121,9 @@ void initESPNow() std::memcpy(peer.peer_addr, broadcast_address, sizeof(peer.peer_addr)); peer.channel = 0; - if (configs.wifiApEnabled.value) + if (configs.wifiApEnabled.value()) peer.ifidx = WIFI_IF_AP; - else if (configs.wifiStaEnabled.value) + else if (configs.wifiStaEnabled.value()) peer.ifidx = WIFI_IF_STA; else { @@ -217,7 +217,7 @@ void handle() { if (msg.type == "T") { - if (!receiveTimeStamp || !configs.espnow.syncTime.value) + if (!receiveTimeStamp || !configs.espnow.syncTime.value()) goto clear; if (const auto result = cpputils::fromString(msg.content); result) @@ -231,7 +231,7 @@ void handle() } else if (msg.type == "BOBBYT") { - if (!receiveTsFromOtherBobbycars || !configs.espnow.syncTimeWithOthers.value) + if (!receiveTsFromOtherBobbycars || !configs.espnow.syncTimeWithOthers.value()) goto clear; if (const auto result = cpputils::fromString(msg.content); result) @@ -278,7 +278,7 @@ esp_err_t send_espnow_message(std::string_view message) if (initialized < 255) return ESP_ERR_ESPNOW_NOT_INIT; - if (!configs.wifiApEnabled.value && !configs.wifiStaEnabled.value) + if (!configs.wifiApEnabled.value() && !configs.wifiStaEnabled.value()) { return ESP_ERR_ESPNOW_IF; } @@ -291,9 +291,9 @@ esp_err_t send_espnow_message(std::string_view message) for (auto &peer : peers) { - if (configs.wifiApEnabled.value) + if (configs.wifiApEnabled.value()) peer.ifidx = WIFI_IF_AP; - else if (configs.wifiStaEnabled.value) + else if (configs.wifiStaEnabled.value()) peer.ifidx = WIFI_IF_STA; else return ESP_ERR_ESPNOW_IF; diff --git a/main/ledstrip.cpp b/main/ledstrip.cpp index 059fd88..fb90bcd 100644 --- a/main/ledstrip.cpp +++ b/main/ledstrip.cpp @@ -27,9 +27,9 @@ namespace { void initLedStrip() { - if (configs.feature.ledstrip.isEnabled.value) + if (configs.feature.ledstrip.isEnabled.value()) { - leds.resize(configs.ledstrip.ledsCount.value); + leds.resize(configs.ledstrip.ledsCount.value()); FastLED.addLeds(&*std::begin(leds), leds.size()) .setCorrection(TypicalSMD5050); initialized = true; @@ -38,29 +38,29 @@ void initLedStrip() void updateLedStrip() { - if (configs.feature.ledstrip.isEnabled.value && !initialized) + if (configs.feature.ledstrip.isEnabled.value() && !initialized) initLedStrip(); - else if (!configs.feature.ledstrip.isEnabled.value && initialized) + else if (!configs.feature.ledstrip.isEnabled.value() && initialized) { std::fill(std::begin(leds), std::end(leds), CRGB::Black); FastLED.show(); initialized = false; return; } - else if (!configs.feature.ledstrip.isEnabled.value) + else if (!configs.feature.ledstrip.isEnabled.value()) return; EVERY_N_MILLISECONDS( 20 ) { gHue++; } static bool have_disabled_beeper = false; - const bool enAnim = configs.ledstrip.enableAnimBlink.value; + const bool enAnim = configs.ledstrip.enableAnimBlink.value(); if (cpputils::is_in(blinkAnimation, LEDSTRIP_OVERWRITE_BLINKLEFT, LEDSTRIP_OVERWRITE_BLINKRIGHT, LEDSTRIP_OVERWRITE_BLINKBOTH)) { std::fill(std::begin(leds), std::end(leds), CRGB{0, 0, 0}); if (espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms || enAnim) { - const auto anim_to_fill = time_to_percent(750ms, 500ms, 100ms, configs.ledstrip.enableFullBlink.value ? (leds.size() / 2) : configs.ledstrip.bigOffset.value - configs.ledstrip.smallOffset.value, configs.ledstrip.enableFullBlink.value); - if (configs.ledstrip.enableBeepWhenBlink.value) + const auto anim_to_fill = time_to_percent(750ms, 500ms, 100ms, configs.ledstrip.enableFullBlink.value() ? (leds.size() / 2) : configs.ledstrip.bigOffset.value() - configs.ledstrip.smallOffset.value(), configs.ledstrip.enableFullBlink.value()); + if (configs.ledstrip.enableBeepWhenBlink.value()) { if (espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms) for (Controller &controller : controllers) @@ -70,9 +70,9 @@ void updateLedStrip() controller.command.buzzer.freq = 0; } auto color = CRGB{255, 200, 0}; - const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value); + const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value()); - if (configs.ledstrip.enableFullBlink.value) + if (configs.ledstrip.enableFullBlink.value()) { // Full if (BLINK_LEFT_EXPR) @@ -108,11 +108,11 @@ void updateLedStrip() // Blink left if (!enAnim) { - std::fill(center - configs.ledstrip.bigOffset.value, center - configs.ledstrip.smallOffset.value, color); + std::fill(center - configs.ledstrip.bigOffset.value(), center - configs.ledstrip.smallOffset.value(), color); } else { - std::fill(center - configs.ledstrip.smallOffset.value - anim_to_fill, center - configs.ledstrip.smallOffset.value, color); + std::fill(center - configs.ledstrip.smallOffset.value() - anim_to_fill, center - configs.ledstrip.smallOffset.value(), color); } } if (BLINK_RIGHT_EXPR) @@ -120,16 +120,16 @@ void updateLedStrip() // Blink right if (!enAnim) { - std::fill(center + configs.ledstrip.smallOffset.value, center + configs.ledstrip.bigOffset.value, color); + std::fill(center + configs.ledstrip.smallOffset.value(), center + configs.ledstrip.bigOffset.value(), color); } else { - std::fill(center + configs.ledstrip.smallOffset.value, center + configs.ledstrip.smallOffset.value + anim_to_fill, color); + std::fill(center + configs.ledstrip.smallOffset.value(), center + configs.ledstrip.smallOffset.value() + anim_to_fill, color); } } } } else { - if (configs.ledstrip.enableBeepWhenBlink.value) + if (configs.ledstrip.enableBeepWhenBlink.value()) { for (Controller &controller : controllers) controller.command.buzzer.freq = 0; @@ -138,7 +138,7 @@ void updateLedStrip() } else { - if (configs.ledstrip.enableBrakeLights.value) + if (configs.ledstrip.enableBrakeLights.value()) { float avgPwm{}; for (const Controller &controller : controllers) @@ -153,17 +153,17 @@ void updateLedStrip() { auto color = avgSpeedKmh < -0.1f ? CRGB{255, 255, 255} : CRGB{255, 0, 0}; - const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value); + const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value()); std::fill(std::begin(leds), std::end(leds), CRGB{0, 0, 0}); - if (configs.ledstrip.enableFullBlink.value) + if (configs.ledstrip.enableFullBlink.value()) { std::fill(std::begin(leds), std::end(leds), color); } - else if(!configs.ledstrip.enableAnimBlink.value) + else if(!configs.ledstrip.enableAnimBlink.value()) { - std::fill(center - configs.ledstrip.bigOffset.value - 2, center - configs.ledstrip.smallOffset.value + 2, color); - std::fill(center + configs.ledstrip.smallOffset.value - 2, center + configs.ledstrip.bigOffset.value + 2, color); + std::fill(center - configs.ledstrip.bigOffset.value() - 2, center - configs.ledstrip.smallOffset.value() + 2, color); + std::fill(center + configs.ledstrip.smallOffset.value() - 2, center + configs.ledstrip.bigOffset.value() + 2, color); } } else @@ -177,51 +177,51 @@ void updateLedStrip() } } - if (!have_disabled_beeper && (!(cpputils::is_in(blinkAnimation, LEDSTRIP_OVERWRITE_BLINKLEFT, LEDSTRIP_OVERWRITE_BLINKRIGHT, LEDSTRIP_OVERWRITE_BLINKBOTH)) || !configs.ledstrip.enableBeepWhenBlink.value)) + if (!have_disabled_beeper && (!(cpputils::is_in(blinkAnimation, LEDSTRIP_OVERWRITE_BLINKLEFT, LEDSTRIP_OVERWRITE_BLINKRIGHT, LEDSTRIP_OVERWRITE_BLINKBOTH)) || !configs.ledstrip.enableBeepWhenBlink.value())) { for (Controller &controller : controllers) controller.command.buzzer.freq = 0; have_disabled_beeper = true; } - else if ((cpputils::is_in(blinkAnimation, LEDSTRIP_OVERWRITE_BLINKLEFT, LEDSTRIP_OVERWRITE_BLINKRIGHT, LEDSTRIP_OVERWRITE_BLINKBOTH)) && configs.ledstrip.enableBeepWhenBlink.value) have_disabled_beeper = false; + else if ((cpputils::is_in(blinkAnimation, LEDSTRIP_OVERWRITE_BLINKLEFT, LEDSTRIP_OVERWRITE_BLINKRIGHT, LEDSTRIP_OVERWRITE_BLINKBOTH)) && configs.ledstrip.enableBeepWhenBlink.value()) have_disabled_beeper = false; const auto automaticLight = activateAutomaticFrontLight(); - if (simplified || configs.ledstrip.enableStVO.value || automaticLight) + if (simplified || configs.ledstrip.enableStVO.value() || automaticLight) { - const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value); + const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value()); - if (!(blinkAnimation == LEDSTRIP_OVERWRITE_BLINKLEFT || blinkAnimation == LEDSTRIP_OVERWRITE_BLINKBOTH) || !(espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms) || configs.ledstrip.enableFullBlink.value) // Condition for right + if (!(blinkAnimation == LEDSTRIP_OVERWRITE_BLINKLEFT || blinkAnimation == LEDSTRIP_OVERWRITE_BLINKBOTH) || !(espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms) || configs.ledstrip.enableFullBlink.value()) // Condition for right { - std::fill(center - configs.ledstrip.bigOffset.value, center - configs.ledstrip.smallOffset.value, CRGB{0, 0, 0}); - std::fill(center - configs.ledstrip.bigOffset.value - 1U, center - configs.ledstrip.smallOffset.value - 1U, CRGB{255, 0, 0}); // Right + std::fill(center - configs.ledstrip.bigOffset.value(), center - configs.ledstrip.smallOffset.value(), CRGB{0, 0, 0}); + std::fill(center - configs.ledstrip.bigOffset.value() - 1U, center - configs.ledstrip.smallOffset.value() - 1U, CRGB{255, 0, 0}); // Right } - if (!(blinkAnimation == LEDSTRIP_OVERWRITE_BLINKRIGHT || blinkAnimation == LEDSTRIP_OVERWRITE_BLINKBOTH) || !(espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms) || configs.ledstrip.enableFullBlink.value) // Condition for left + if (!(blinkAnimation == LEDSTRIP_OVERWRITE_BLINKRIGHT || blinkAnimation == LEDSTRIP_OVERWRITE_BLINKBOTH) || !(espchrono::utc_clock::now().time_since_epoch() % 750ms < 375ms) || configs.ledstrip.enableFullBlink.value()) // Condition for left { - std::fill(center + configs.ledstrip.smallOffset.value, center + configs.ledstrip.bigOffset.value, CRGB{0, 0, 0}); - std::fill(center + configs.ledstrip.smallOffset.value + 1U, center + configs.ledstrip.bigOffset.value + 1U, CRGB{255, 0, 0}); // Left + std::fill(center + configs.ledstrip.smallOffset.value(), center + configs.ledstrip.bigOffset.value(), CRGB{0, 0, 0}); + std::fill(center + configs.ledstrip.smallOffset.value() + 1U, center + configs.ledstrip.bigOffset.value() + 1U, CRGB{255, 0, 0}); // Left } - if (configs.ledstrip.stvoFrontEnable.value || automaticLight) + if (configs.ledstrip.stvoFrontEnable.value() || automaticLight) { - std::fill(std::begin(leds) + configs.ledstrip.stvoFrontOffset.value, std::begin(leds) + configs.ledstrip.stvoFrontOffset.value + configs.ledstrip.stvoFrontLength.value, CRGB{255, 255, 255}); - std::fill(std::end(leds) - configs.ledstrip.stvoFrontOffset.value - configs.ledstrip.stvoFrontLength.value, std::end(leds) - configs.ledstrip.stvoFrontOffset.value, CRGB{255, 255, 255}); + std::fill(std::begin(leds) + configs.ledstrip.stvoFrontOffset.value(), std::begin(leds) + configs.ledstrip.stvoFrontOffset.value() + configs.ledstrip.stvoFrontLength.value(), CRGB{255, 255, 255}); + std::fill(std::end(leds) - configs.ledstrip.stvoFrontOffset.value() - configs.ledstrip.stvoFrontLength.value(), std::end(leds) - configs.ledstrip.stvoFrontOffset.value(), CRGB{255, 255, 255}); } } - FastLED.setMaxPowerInVoltsAndMilliamps(5, configs.ledstrip.maxMilliamps.value); - FastLED.setBrightness(configs.ledstrip.brightness.value); + FastLED.setMaxPowerInVoltsAndMilliamps(5, configs.ledstrip.maxMilliamps.value()); + FastLED.setBrightness(configs.ledstrip.brightness.value()); FastLED.show(); } void showAnimation() { - if (configs.ledstrip.enableLedAnimation.value + if (configs.ledstrip.enableLedAnimation.value() && !simplified - && !(asyncOtaTaskStarted && configs.ledstrip.otaMode.value != OtaAnimationModes::None) + && !(asyncOtaTaskStarted && configs.ledstrip.otaMode.value() != OtaAnimationModes::None) ) { - switch (configs.ledstrip.animationType.value) + switch (configs.ledstrip.animationType.value()) { case LedstripAnimation::DefaultRainbow: showDefaultLedstrip(); break; case LedstripAnimation::BetterRainbow: showBetterRainbow(); break; @@ -232,7 +232,7 @@ void showAnimation() default: showDefaultLedstrip(); } } - else if (asyncOtaTaskStarted && configs.ledstrip.otaMode.value != OtaAnimationModes::None) + else if (asyncOtaTaskStarted && configs.ledstrip.otaMode.value() != OtaAnimationModes::None) { // show ota animation showOtaAnimation(); @@ -253,7 +253,7 @@ void showOtaAnimation() if (const auto totalSize = asyncOta->totalSize(); totalSize && *totalSize > 0) { percentage = (float(progress) / *totalSize * 100); - if (configs.ledstrip.otaMode.value == OtaAnimationModes::GreenProgressBar) + if (configs.ledstrip.otaMode.value() == OtaAnimationModes::GreenProgressBar) { int numLeds = (leds_count * percentage) / 100; if (numLeds >= leds_count) @@ -262,7 +262,7 @@ void showOtaAnimation() } std::fill(std::begin(leds), std::begin(leds) + numLeds, CRGB{0,255,0}); } - else if (configs.ledstrip.otaMode.value == OtaAnimationModes::ColorChangeAll) + else if (configs.ledstrip.otaMode.value() == OtaAnimationModes::ColorChangeAll) { const uint8_t redChannel = 255 - (2.55 * percentage); const uint8_t greenChannel = 2.55 * percentage; @@ -307,9 +307,9 @@ void showSpeedSyncAnimation() static float hue_result = 0; - const float hue_per_led = 1. / std::max(uint8_t(1), uint8_t(configs.ledstrip.animationMultiplier.value)); + const float hue_per_led = 1. / std::max(uint8_t(1), uint8_t(configs.ledstrip.animationMultiplier.value())); const float meter_per_second = avgSpeedKmh / 3.6; - const float leds_per_second = meter_per_second * configs.ledstrip.leds_per_meter.value; + const float leds_per_second = meter_per_second * configs.ledstrip.leds_per_meter.value(); const float hue_per_second = leds_per_second * hue_per_led; hue_result += hue_per_second * difference_ms / 1000.f; @@ -333,7 +333,7 @@ void showDefaultLedstrip() void showSnakeAnimation() { - const float leds_per_cycle = (1. / std::max(1, configs.ledstrip.animationMultiplier.value)) * (avgSpeedKmh + 1); // yes, this is intendet as a float value! Do NOT change! + const float leds_per_cycle = (1. / std::max(1, configs.ledstrip.animationMultiplier.value())) * (avgSpeedKmh + 1); // yes, this is intendet as a float value! Do NOT change! fadeToBlackBy(&*std::begin(leds), leds.size(), floor(20*leds_per_cycle)); if (gLedPosition >= leds.size()) { @@ -402,40 +402,40 @@ void showGasOMeterAnimation() void showCustomColor() { const auto eighth_length = leds.size() / 8; - const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value); + const auto center = (std::begin(leds) + (leds.size() / 2) + configs.ledstrip.centerOffset.value()); - std::fill(std::begin(leds), std::end(leds), configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT)].value); // Front - std::fill(center - (eighth_length / 2), center + (eighth_length / 2), configs.ledstrip.custom_color[int(Bobbycar_Side::BACK)].value); // Back + std::fill(std::begin(leds), std::end(leds), configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT)].value()); // Front + std::fill(center - (eighth_length / 2), center + (eighth_length / 2), configs.ledstrip.custom_color[int(Bobbycar_Side::BACK)].value()); // Back #ifdef LEDSTRIP_WRONG_DIRECTION - std::fill(center + (eighth_length / 2), center + (eighth_length / 2) + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_LEFT)].value); // Back Left - std::fill(center - (eighth_length / 2) - eighth_length, center - (eighth_length / 2), configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_RIGHT)].value); // Back Right + std::fill(center + (eighth_length / 2), center + (eighth_length / 2) + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_LEFT)].value()); // Back Left + std::fill(center - (eighth_length / 2) - eighth_length, center - (eighth_length / 2), configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_RIGHT)].value()); // Back Right #else - std::fill(center + (eighth_length / 2), center + (eighth_length / 2) + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_RIGHT)].value); // Back Right - std::fill(center - (eighth_length / 2) - eighth_length, center - (eighth_length / 2), configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_LEFT)].value); // Back Left + std::fill(center + (eighth_length / 2), center + (eighth_length / 2) + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_RIGHT)].value()); // Back Right + std::fill(center - (eighth_length / 2) - eighth_length, center - (eighth_length / 2), configs.ledstrip.custom_color[int(Bobbycar_Side::BACK_LEFT)].value()); // Back Left #endif #ifdef LEDSTRIP_WRONG_DIRECTION - std::fill(center + (eighth_length / 2) + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::LEFT)].value); // Left - std::fill(center - (eighth_length / 2) - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::RIGHT)].value); // Right + std::fill(center + (eighth_length / 2) + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::LEFT)].value()); // Left + std::fill(center - (eighth_length / 2) - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::RIGHT)].value()); // Right #else - std::fill(center + (eighth_length / 2) + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::RIGHT)].value); // Right - std::fill(center - (eighth_length / 2) - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::LEFT)].value); // Left + std::fill(center + (eighth_length / 2) + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::RIGHT)].value()); // Right + std::fill(center - (eighth_length / 2) - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::LEFT)].value()); // Left #endif #ifdef LEDSTRIP_WRONG_DIRECTION - std::fill(center + (eighth_length / 2) + eighth_length + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_LEFT)].value); // Front Left - std::fill(center - (eighth_length / 2) - eighth_length - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_RIGHT)].value); // Front Right + std::fill(center + (eighth_length / 2) + eighth_length + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_LEFT)].value()); // Front Left + std::fill(center - (eighth_length / 2) - eighth_length - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_RIGHT)].value()); // Front Right #else - std::fill(center + (eighth_length / 2) + eighth_length + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_RIGHT)].value); // Front Right - std::fill(center - (eighth_length / 2) - eighth_length - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_LEFT)].value); // Front Left + std::fill(center + (eighth_length / 2) + eighth_length + eighth_length, center + (eighth_length / 2) + eighth_length + eighth_length + eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_RIGHT)].value()); // Front Right + std::fill(center - (eighth_length / 2) - eighth_length - eighth_length - eighth_length, center - (eighth_length / 2) - eighth_length - eighth_length, configs.ledstrip.custom_color[int(Bobbycar_Side::FRONT_LEFT)].value()); // Front Left #endif } [[nodiscard]] bool activateAutomaticFrontLight() { using namespace std::chrono_literals; - if (!configs.ledstrip.automaticLight.value) + if (!configs.ledstrip.automaticLight.value()) return false; const auto today = toDateTime(espchrono::utc_clock::now()); diff --git a/main/main.cpp b/main/main.cpp index c966a44..e463065 100644 --- a/main/main.cpp +++ b/main/main.cpp @@ -80,14 +80,14 @@ extern "C" void app_main() bootLabel.redraw("switchScreen"); - if (configs.dpadMappingLeft.value == INPUT_MAPPING_NONE || - configs.dpadMappingRight.value == INPUT_MAPPING_NONE || - configs.dpadMappingUp.value == INPUT_MAPPING_NONE || - configs.dpadMappingDown.value == INPUT_MAPPING_NONE) + if (configs.dpadMappingLeft.value() == INPUT_MAPPING_NONE || + configs.dpadMappingRight.value() == INPUT_MAPPING_NONE || + configs.dpadMappingUp.value() == INPUT_MAPPING_NONE || + configs.dpadMappingDown.value() == INPUT_MAPPING_NONE) { espgui::switchScreen(true); } - else if (configs.lockscreen.keepLockedAfterReboot.value && configs.lockscreen.locked.value) + else if (configs.lockscreen.keepLockedAfterReboot.value() && configs.lockscreen.locked.value()) { espgui::switchScreen(); } @@ -114,7 +114,7 @@ extern "C" void app_main() schedulerTask.loop(); } - if (!lastStatsUpdate || now - *lastStatsUpdate >= 1000ms/configs.boardcomputerHardware.timersSettings.statsUpdateRate.value) + if (!lastStatsUpdate || now - *lastStatsUpdate >= 1000ms/configs.boardcomputerHardware.timersSettings.statsUpdateRate.value()) { updateAccumulators(); pushStats(); @@ -136,7 +136,7 @@ extern "C" void app_main() { if (avgVoltage > 30) { - battery::bootBatPercentage = getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value)); + battery::bootBatPercentage = getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value())); battery::bootBatWh = getRemainingWattHours(); } } diff --git a/main/modes/defaultmode.cpp b/main/modes/defaultmode.cpp index 0632cd8..39f9b67 100644 --- a/main/modes/defaultmode.cpp +++ b/main/modes/defaultmode.cpp @@ -59,7 +59,7 @@ void DefaultMode::update() float pwm; - if (configs.handbremse.enable.value && handbremse::stateWish == handbremse::StateWish::brake) + if (configs.handbremse.enable.value() && handbremse::stateWish == handbremse::StateWish::brake) { using namespace handbremse; @@ -72,7 +72,7 @@ void DefaultMode::update() } } - if (configs.handbremse.enable.value && configs.handbremse.automatic.value && !handbremse::angezogen) + if (configs.handbremse.enable.value() && configs.handbremse.automatic.value() && !handbremse::angezogen) { using namespace handbremse; const auto speed = abs(avgSpeedKmh); @@ -88,7 +88,7 @@ void DefaultMode::update() standStillFirstDetected = std::nullopt; if (standStillFirstDetected && lastAutoRelease) - if (espchrono::ago(*standStillFirstDetected) > 100ms * configs.handbremse.triggerTimeout.value && espchrono::ago(*lastAutoRelease) > 5s ) + if (espchrono::ago(*standStillFirstDetected) > 100ms * configs.handbremse.triggerTimeout.value() && espchrono::ago(*lastAutoRelease) > 5s ) { angezogen = true; } @@ -152,7 +152,7 @@ void DefaultMode::update() for (bobbycar::protocol::serial::MotorState &motor : motors()) { motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl; - switch (configs.handbremse.mode.value) + switch (configs.handbremse.mode.value()) { case HandbremseMode::MOSFETS_OFF: motor.ctrlMod = bobbycar::protocol::ControlMode::Torque; diff --git a/main/modes/wheelchairmode.cpp b/main/modes/wheelchairmode.cpp index a50a164..2c17e5c 100644 --- a/main/modes/wheelchairmode.cpp +++ b/main/modes/wheelchairmode.cpp @@ -33,8 +33,8 @@ void WheelchairMode::update() } else { - const int16_t left_right = configs.gasMin.value == configs.gasMax.value ? 0 : *gas; - const int16_t front_back = configs.bremsMin.value == configs.bremsMax.value ? 0 : -*brems; + const int16_t left_right = configs.gasMin.value() == configs.gasMax.value() ? 0 : *gas; + const int16_t front_back = configs.bremsMin.value() == configs.bremsMax.value() ? 0 : -*brems; float local_gas = 0; float local_brems = 0; @@ -69,7 +69,7 @@ void WheelchairMode::update() float pwm; - if (configs.handbremse.enable.value && handbremse::stateWish == handbremse::StateWish::brake) + if (configs.handbremse.enable.value() && handbremse::stateWish == handbremse::StateWish::brake) { using namespace handbremse; @@ -82,7 +82,7 @@ void WheelchairMode::update() } } - if (configs.handbremse.enable.value && configs.handbremse.automatic.value && !handbremse::angezogen) + if (configs.handbremse.enable.value() && configs.handbremse.automatic.value() && !handbremse::angezogen) { using namespace handbremse; const auto speed = abs(avgSpeedKmh); @@ -98,7 +98,7 @@ void WheelchairMode::update() standStillFirstDetected = std::nullopt; if (standStillFirstDetected && lastAutoRelease) - if (espchrono::ago(*standStillFirstDetected) > 100ms * configs.handbremse.triggerTimeout.value && espchrono::ago(*lastAutoRelease) > 5s ) + if (espchrono::ago(*standStillFirstDetected) > 100ms * configs.handbremse.triggerTimeout.value() && espchrono::ago(*lastAutoRelease) > 5s ) { angezogen = true; } @@ -162,7 +162,7 @@ void WheelchairMode::update() for (bobbycar::protocol::serial::MotorState &motor : motors()) { motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl; - switch (configs.handbremse.mode.value) + switch (configs.handbremse.mode.value()) { case HandbremseMode::MOSFETS_OFF: motor.ctrlMod = bobbycar::protocol::ControlMode::Torque; diff --git a/main/newsettings.h b/main/newsettings.h index 047a946..bda9bb3 100644 --- a/main/newsettings.h +++ b/main/newsettings.h @@ -34,6 +34,103 @@ std::string defaultHostname(); constexpr const auto INPUT_MAPPING_NONE = std::numeric_limits::max(); +enum class AllowReset { NoReset, DoReset }; +constexpr auto NoReset = AllowReset::NoReset; +constexpr auto DoReset = AllowReset::DoReset; + +template +class ConfigWrapperLegacy final : public ConfigWrapper +{ + CPP_DISABLE_COPY_MOVE(ConfigWrapperLegacy) + using Base = ConfigWrapper; + +public: + using value_t = typename Base::value_t; + using ConstraintCallback = typename Base::ConstraintCallback; + + using DefaultValueCallbackRef = T(&)(); + using DefaultValueCallbackPtr = T(*)(); + + ConfigWrapperLegacy(const T &defaultValue, AllowReset allowReset, ConstraintCallback constraintCallback, const char *nvsName) : + m_allowReset{allowReset == AllowReset::DoReset}, + m_nvsName{nvsName}, + m_defaultType{DefaultByValue}, + m_defaultValue{defaultValue}, + m_constraintCallback{constraintCallback} + {} + + ConfigWrapperLegacy(T &&defaultValue, AllowReset allowReset, ConstraintCallback constraintCallback, const char *nvsName) : + m_allowReset{allowReset == AllowReset::DoReset}, + m_nvsName{nvsName}, + m_defaultType{DefaultByValue}, + m_defaultValue{std::move(defaultValue)}, + m_constraintCallback{constraintCallback} + {} + + ConfigWrapperLegacy(const ConfigWrapper &factoryConfig, ConstraintCallback constraintCallback, const char *nvsName) : + m_allowReset{true}, + m_nvsName{nvsName}, + m_defaultType{DefaultByFactoryConfig}, + m_factoryConfig{&factoryConfig}, + m_constraintCallback{constraintCallback} + {} + + ConfigWrapperLegacy(const DefaultValueCallbackRef &defaultCallback, AllowReset allowReset, ConstraintCallback constraintCallback, const char *nvsName) : + m_allowReset{allowReset == AllowReset::DoReset}, + m_nvsName{nvsName}, + m_defaultType{DefaultByCallback}, + m_defaultCallback{&defaultCallback}, + m_constraintCallback{constraintCallback} + {} + + ~ConfigWrapperLegacy() + { + switch (m_defaultType) + { + case DefaultByValue: m_defaultValue.~T(); break; + case DefaultByFactoryConfig: /*m_factoryConfig.~typeof(m_factoryConfig)();*/ break; + case DefaultByCallback: /*m_defaultCallback.~typeof(m_defaultCallback)();*/ break; + } + } + + const char *nvsName() const override final { return m_nvsName; } + bool allowReset() const override final { return m_allowReset; } + T defaultValue() const override final + { + switch (m_defaultType) + { + case DefaultByValue: return m_defaultValue; + case DefaultByFactoryConfig: assert(m_factoryConfig->loaded()); return m_factoryConfig->value(); + case DefaultByCallback: return m_defaultCallback(); + } + + __builtin_unreachable(); + } + + ConfigConstraintReturnType checkValue(value_t value) const override final + { + if (!m_constraintCallback) + return {}; + + return m_constraintCallback(value); + } + +private: + const bool m_allowReset; + const char * const m_nvsName; + + const enum : uint8_t { DefaultByValue, DefaultByFactoryConfig, DefaultByCallback } m_defaultType; + + union + { + const T m_defaultValue; + const ConfigWrapper * const m_factoryConfig; + const DefaultValueCallbackPtr m_defaultCallback; + }; + + const ConstraintCallback m_constraintCallback; +}; + class WiFiConfig { public: @@ -67,16 +164,16 @@ public: staticDns2 {wifi_stack::ip_address_t{}, DoReset, {}, staticDns2Key } {} - ConfigWrapper ssid; - ConfigWrapper key; - ConfigWrapper useStaticIp; - ConfigWrapper staticIp; - ConfigWrapper staticSubnet; - ConfigWrapper staticGateway; - ConfigWrapper useStaticDns; - ConfigWrapper staticDns0; - ConfigWrapper staticDns1; - ConfigWrapper staticDns2; + ConfigWrapperLegacy ssid; + ConfigWrapperLegacy key; + ConfigWrapperLegacy useStaticIp; + ConfigWrapperLegacy staticIp; + ConfigWrapperLegacy staticSubnet; + ConfigWrapperLegacy staticGateway; + ConfigWrapperLegacy useStaticDns; + ConfigWrapperLegacy staticDns0; + ConfigWrapperLegacy staticDns1; + ConfigWrapperLegacy staticDns2; }; class WirelessDoorsConfig @@ -87,8 +184,8 @@ public: doorToken {std::string{}, DoReset, StringMaxSize<24>, doorTokenKey } {} - ConfigWrapper doorId; - ConfigWrapper doorToken; + ConfigWrapperLegacy doorId; + ConfigWrapperLegacy doorToken; }; class ConfiguredOtaServer @@ -99,8 +196,8 @@ public: url {std::string{}, DoReset, StringOr, urlKey } {} - ConfigWrapper name; - ConfigWrapper url; + ConfigWrapperLegacy name; + ConfigWrapperLegacy url; }; class ConfiguredFeatureFlag @@ -112,7 +209,7 @@ public: m_taskName{taskName} {} - ConfigWrapper isEnabled; + ConfigWrapperLegacy isEnabled; bool isBeta() const { return m_isBeta; } std::string getTaskName() const { return m_taskName; } private: @@ -126,9 +223,9 @@ class ConfigContainer public: // default allowReset constraints nvsName - ConfigWrapper> baseMacAddressOverride{std::nullopt, DoReset, {}, "baseMacAddrOver" }; - ConfigWrapper hostname {defaultHostname, DoReset, StringMinMaxSize<4, 32>, "hostname" }; - ConfigWrapper wifiStaEnabled {true, DoReset, {}, "wifiStaEnabled" }; + ConfigWrapperLegacy> baseMacAddressOverride{std::nullopt, DoReset, {}, "baseMacAddrOver" }; + ConfigWrapperLegacy hostname {defaultHostname, DoReset, StringMinMaxSize<4, 32>, "hostname" }; + ConfigWrapperLegacy wifiStaEnabled {true, DoReset, {}, "wifiStaEnabled" }; std::array wifi_configs { WiFiConfig {"wifi_ssid0", "wifi_key0", "wifi_usestatic0", "wifi_static_ip0", "wifi_stati_sub0", "wifi_stat_gate0", "wifi_usestadns0", "wifi_stat_dnsA0", "wifi_stat_dnsB0", "wifi_stat_dnsC0", "bobbycar", "12345678"}, WiFiConfig {"wifi_ssid1", "wifi_key1", "wifi_usestatic1", "wifi_static_ip1", "wifi_stati_sub1", "wifi_stat_gate1", "wifi_usestadns1", "wifi_stat_dnsA1", "wifi_stat_dnsB1", "wifi_stat_dnsC1"}, @@ -141,63 +238,63 @@ public: WiFiConfig {"wifi_ssid8", "wifi_key8", "wifi_usestatic8", "wifi_static_ip8", "wifi_stati_sub8", "wifi_stat_gate8", "wifi_usestadns8", "wifi_stat_dnsA8", "wifi_stat_dnsB8", "wifi_stat_dnsC8"}, WiFiConfig {"wifi_ssid9", "wifi_key9", "wifi_usestatic9", "wifi_static_ip9", "wifi_stati_sub9", "wifi_stat_gate9", "wifi_usestadns9", "wifi_stat_dnsA9", "wifi_stat_dnsB9", "wifi_stat_dnsC9"} }; - ConfigWrapper wifiStaMinRssi {-90, DoReset, {}, "wifiStaMinRssi" }; + ConfigWrapperLegacy wifiStaMinRssi {-90, DoReset, {}, "wifiStaMinRssi" }; - ConfigWrapper wifiApEnabled {true, DoReset, {}, "wifiApEnabled" }; - ConfigWrapper wifiApName {defaultHostname, DoReset, StringMinMaxSize<4, 32>, "wifiApName" }; - ConfigWrapper wifiApKey {"Passwort_123", DoReset, StringOr>, "wifiApKey" }; - ConfigWrapper wifiApIp{wifi_stack::ip_address_t{10, 0, 0, 1},DoReset, {}, "wifiApIp" }; - ConfigWrapper wifiApMask{wifi_stack::ip_address_t{255, 255, 255, 0},DoReset, {}, "wifiApMask" }; - ConfigWrapper wifiApChannel {1, DoReset, MinMaxValue, "wifiApChannel" }; - ConfigWrapper wifiApAuthmode{WIFI_AUTH_WPA2_PSK, DoReset, {}, "wifiApAuthmode" }; + ConfigWrapperLegacy wifiApEnabled {true, DoReset, {}, "wifiApEnabled" }; + ConfigWrapperLegacy wifiApName {defaultHostname, DoReset, StringMinMaxSize<4, 32>, "wifiApName" }; + ConfigWrapperLegacy wifiApKey {"Passwort_123", DoReset, StringOr>, "wifiApKey" }; + ConfigWrapperLegacy wifiApIp{wifi_stack::ip_address_t{10, 0, 0, 1},DoReset, {}, "wifiApIp" }; + ConfigWrapperLegacy wifiApMask{wifi_stack::ip_address_t{255, 255, 255, 0},DoReset, {}, "wifiApMask" }; + ConfigWrapperLegacy wifiApChannel {1, DoReset, MinMaxValue, "wifiApChannel" }; + ConfigWrapperLegacy wifiApAuthmode{WIFI_AUTH_WPA2_PSK, DoReset, {}, "wifiApAuthmode" }; - ConfigWrapper timeServerEnabled {true, DoReset, {}, "timeServerEnabl" }; - ConfigWrapper timeServer {"europe.pool.ntp.org", DoReset, StringMaxSize<64>, "timeServer" }; - ConfigWrapper timeSyncMode {SNTP_SYNC_MODE_IMMED, DoReset, {}, "timeSyncMode" }; - ConfigWrapper timeSyncInterval{espchrono::milliseconds32{CONFIG_LWIP_SNTP_UPDATE_DELAY}, DoReset, MinTimeSyncInterval, "timeSyncInterva" }; - ConfigWrapper timezoneOffset{espchrono::minutes32{60}, DoReset, {}, "timezoneOffset" }; // MinMaxValue - ConfigWrappertimeDst{espchrono::DayLightSavingMode::EuropeanSummerTime, DoReset, {}, "time_dst" }; + ConfigWrapperLegacy timeServerEnabled {true, DoReset, {}, "timeServerEnabl" }; + ConfigWrapperLegacy timeServer {"europe.pool.ntp.org", DoReset, StringMaxSize<64>, "timeServer" }; + ConfigWrapperLegacy timeSyncMode {SNTP_SYNC_MODE_IMMED, DoReset, {}, "timeSyncMode" }; + ConfigWrapperLegacy timeSyncInterval{espchrono::milliseconds32{CONFIG_LWIP_SNTP_UPDATE_DELAY}, DoReset, MinTimeSyncInterval, "timeSyncInterva" }; + ConfigWrapperLegacy timezoneOffset{espchrono::minutes32{60}, DoReset, {}, "timezoneOffset" }; // MinMaxValue + ConfigWrapperLegacytimeDst{espchrono::DayLightSavingMode::EuropeanSummerTime, DoReset, {}, "time_dst" }; - ConfigWrapper canResetOnError {false, DoReset, {}, "canBusRstErr" }; - ConfigWrapper canUninstallOnReset {false, DoReset, {}, "canUnstlRstErr" }; + ConfigWrapperLegacy canResetOnError {false, DoReset, {}, "canBusRstErr" }; + ConfigWrapperLegacy canUninstallOnReset {false, DoReset, {}, "canUnstlRstErr" }; - ConfigWrapper sampleCount {50, DoReset, {}, "sampleCount" }; - ConfigWrapper gasMin {0, DoReset, MinMaxValue, "gasMin" }; - ConfigWrapper gasMax {4095, DoReset, MinMaxValue, "gasMax" }; - ConfigWrapper gasMitte {2048, DoReset, MinMaxValue, "gasMiddle" }; - ConfigWrapper bremsMin {0, DoReset, MinMaxValue, "bremsMin" }; - ConfigWrapper bremsMax {4096, DoReset, MinMaxValue, "bremsMax" }; - ConfigWrapper bremsMitte {2048, DoReset, MinMaxValue, "bremsMiddle" }; - ConfigWrapper deadband {20, DoReset, MinMaxValue,"deadband" }; + ConfigWrapperLegacy sampleCount {50, DoReset, {}, "sampleCount" }; + ConfigWrapperLegacy gasMin {0, DoReset, MinMaxValue, "gasMin" }; + ConfigWrapperLegacy gasMax {4095, DoReset, MinMaxValue, "gasMax" }; + ConfigWrapperLegacy gasMitte {2048, DoReset, MinMaxValue, "gasMiddle" }; + ConfigWrapperLegacy bremsMin {0, DoReset, MinMaxValue, "bremsMin" }; + ConfigWrapperLegacy bremsMax {4096, DoReset, MinMaxValue, "bremsMax" }; + ConfigWrapperLegacy bremsMitte {2048, DoReset, MinMaxValue, "bremsMiddle" }; + ConfigWrapperLegacy deadband {20, DoReset, MinMaxValue,"deadband" }; - ConfigWrapper dpadDebounce {25, DoReset, {}, "dpadDebounce" }; - ConfigWrapper buttonReadDelay {1, DoReset, {}, "buttonDelay" }; + ConfigWrapperLegacy dpadDebounce {25, DoReset, {}, "dpadDebounce" }; + ConfigWrapperLegacy buttonReadDelay {1, DoReset, {}, "buttonDelay" }; - ConfigWrapper dpadMappingLeft {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapLeft" }; - ConfigWrapper dpadMappingRight {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapRight" }; - ConfigWrapper dpadMappingUp {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapUp" }; - ConfigWrapper dpadMappingDown {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapDown" }; - ConfigWrapper dpadMappingProfile0{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile0" }; - ConfigWrapper dpadMappingProfile1{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile1" }; - ConfigWrapper dpadMappingProfile2{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile2" }; - ConfigWrapper dpadMappingProfile3{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile3" }; - ConfigWrapper dpadMappingLeft2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapLeft2" }; - ConfigWrapper dpadMappingRight2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapRight2" }; - ConfigWrapper dpadMappingUp2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapUp2" }; - ConfigWrapper dpadMappingDown2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapDown2" }; - ConfigWrapper dpadMappingExtra1 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra1" }; - ConfigWrapper dpadMappingExtra2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra2" }; - ConfigWrapper dpadMappingExtra3 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra3" }; - ConfigWrapper dpadMappingExtra4 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra4" }; + ConfigWrapperLegacy dpadMappingLeft {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapLeft" }; + ConfigWrapperLegacy dpadMappingRight {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapRight" }; + ConfigWrapperLegacy dpadMappingUp {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapUp" }; + ConfigWrapperLegacy dpadMappingDown {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapDown" }; + ConfigWrapperLegacy dpadMappingProfile0{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile0" }; + ConfigWrapperLegacy dpadMappingProfile1{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile1" }; + ConfigWrapperLegacy dpadMappingProfile2{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile2" }; + ConfigWrapperLegacy dpadMappingProfile3{INPUT_MAPPING_NONE, DoReset, {}, "dpadMapProfile3" }; + ConfigWrapperLegacy dpadMappingLeft2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapLeft2" }; + ConfigWrapperLegacy dpadMappingRight2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapRight2" }; + ConfigWrapperLegacy dpadMappingUp2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapUp2" }; + ConfigWrapperLegacy dpadMappingDown2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapDown2" }; + ConfigWrapperLegacy dpadMappingExtra1 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra1" }; + ConfigWrapperLegacy dpadMappingExtra2 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra2" }; + ConfigWrapperLegacy dpadMappingExtra3 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra3" }; + ConfigWrapperLegacy dpadMappingExtra4 {INPUT_MAPPING_NONE, DoReset, {}, "dpadMapExtra4" }; - ConfigWrapper quickActionLeft2{ BobbyQuickActions::BLINK_LEFT, DoReset, {}, "quickActleft2" }; - ConfigWrapper quickActionRight2{ BobbyQuickActions::BLINK_RIGHT, DoReset, {}, "quickActright2" }; - ConfigWrapper quickActionUp2{ BobbyQuickActions::NONE, DoReset, {}, "quickActup2" }; - ConfigWrapper quickActionDown2{ BobbyQuickActions::HANDBREMSE, DoReset, {}, "quickActdown2" }; - ConfigWrapper quickActionExtra1{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra1" }; - ConfigWrapper quickActionExtra2{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra2" }; - ConfigWrapper quickActionExtra3{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra3" }; - ConfigWrapper quickActionExtra4{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra4" }; + ConfigWrapperLegacy quickActionLeft2{ BobbyQuickActions::BLINK_LEFT, DoReset, {}, "quickActleft2" }; + ConfigWrapperLegacy quickActionRight2{ BobbyQuickActions::BLINK_RIGHT, DoReset, {}, "quickActright2" }; + ConfigWrapperLegacy quickActionUp2{ BobbyQuickActions::NONE, DoReset, {}, "quickActup2" }; + ConfigWrapperLegacy quickActionDown2{ BobbyQuickActions::HANDBREMSE, DoReset, {}, "quickActdown2" }; + ConfigWrapperLegacy quickActionExtra1{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra1" }; + ConfigWrapperLegacy quickActionExtra2{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra2" }; + ConfigWrapperLegacy quickActionExtra3{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra3" }; + ConfigWrapperLegacy quickActionExtra4{ BobbyQuickActions::NONE, DoReset, {}, "quickActextra4" }; std::array wireless_door_configs { WirelessDoorsConfig { "door_id0", "door_token0" }, @@ -207,21 +304,21 @@ public: WirelessDoorsConfig { "door_id4", "door_token4" } }; - ConfigWrapper bluetoothName {defaultHostname, DoReset, StringMinMaxSize<4, 32>, "bluetoothName" }; + ConfigWrapperLegacy bluetoothName {defaultHostname, DoReset, StringMinMaxSize<4, 32>, "bluetoothName" }; - ConfigWrapper reverseBeep {false, DoReset, {}, "reverseBeep" }; - ConfigWrapper reverseBeepFreq0 {3, DoReset, {}, "revBeepFreq0" }; - ConfigWrapper reverseBeepFreq1 {0, DoReset, {}, "revBeepFreq1" }; - ConfigWrapper reverseBeepDuration0{500, DoReset, {}, "revBeepDur0" }; - ConfigWrapper reverseBeepDuration1{500, DoReset, {}, "revBeepDur1" }; + ConfigWrapperLegacy reverseBeep {false, DoReset, {}, "reverseBeep" }; + ConfigWrapperLegacy reverseBeepFreq0 {3, DoReset, {}, "revBeepFreq0" }; + ConfigWrapperLegacy reverseBeepFreq1 {0, DoReset, {}, "revBeepFreq1" }; + ConfigWrapperLegacy reverseBeepDuration0{500, DoReset, {}, "revBeepDur0" }; + ConfigWrapperLegacy reverseBeepDuration1{500, DoReset, {}, "revBeepDur1" }; - ConfigWrapper cloudUrl {std::string{}, DoReset, StringOr, "cloudUrl" }; - ConfigWrapper udpCloudHost {std::string{}, DoReset, {}, "udpCloudHost" }; + ConfigWrapperLegacy cloudUrl {std::string{}, DoReset, StringOr, "cloudUrl" }; + ConfigWrapperLegacy udpCloudHost {std::string{}, DoReset, {}, "udpCloudHost" }; - ConfigWrapper otaUrl {std::string{}, DoReset, StringOr, "otaUrl" }; - ConfigWrapper otaUsername {std::string{}, DoReset, {}, "otaUsername" }; - ConfigWrapper otaServerUrl {std::string{}, DoReset, StringOr, "otaServerUrl" }; - ConfigWrapper otaServerBranch {std::string{}, DoReset, {}, "otaServerBranch" }; + ConfigWrapperLegacy otaUrl {std::string{}, DoReset, StringOr, "otaUrl" }; + ConfigWrapperLegacy otaUsername {std::string{}, DoReset, {}, "otaUsername" }; + ConfigWrapperLegacy otaServerUrl {std::string{}, DoReset, StringOr, "otaServerUrl" }; + ConfigWrapperLegacy otaServerBranch {std::string{}, DoReset, {}, "otaServerBranch" }; std::array otaServers { ConfiguredOtaServer { "otaName0", "otaUrl0" }, ConfiguredOtaServer { "otaName1", "otaUrl1" }, @@ -230,127 +327,127 @@ public: ConfiguredOtaServer { "otaName4", "otaUrl4" } }; - ConfigWrapper dns_announce_enabled{true, DoReset, {}, "dnsAnnounceEnab" }; - ConfigWrapper dns_announce_key {std::string{}, DoReset, {}, "dnsAnnounceKey" }; - ConfigWrapper webserverPassword {std::string{}, DoReset, {}, "websPassword" }; + ConfigWrapperLegacy dns_announce_enabled{true, DoReset, {}, "dnsAnnounceEnab" }; + ConfigWrapperLegacy dns_announce_key {std::string{}, DoReset, {}, "dnsAnnounceKey" }; + ConfigWrapperLegacy webserverPassword {std::string{}, DoReset, {}, "websPassword" }; struct { - ConfigWrapper wheelDiameter {DEFAULT_WHEELDIAMETER, DoReset, {}, "wheelDiameter" }; - ConfigWrapper numMagnetPoles {15, DoReset, {}, "numMagnetPoles" }; - ConfigWrapper swapFrontBack {false, DoReset, {}, "swapFrontBack" }; - ConfigWrapper sendFrontCanCmd {true, DoReset, {}, "sendFrontCanCmd" }; - ConfigWrapper sendBackCanCmd {true, DoReset, {}, "sendBackCanCmd" }; - ConfigWrapper canTransmitTimeout {200, DoReset, {}, "canTransmitTime" }; - ConfigWrapper canReceiveTimeout {0, DoReset, {}, "canReceiveTimeo" }; + ConfigWrapperLegacy wheelDiameter {DEFAULT_WHEELDIAMETER, DoReset, {}, "wheelDiameter" }; + ConfigWrapperLegacy numMagnetPoles {15, DoReset, {}, "numMagnetPoles" }; + ConfigWrapperLegacy swapFrontBack {false, DoReset, {}, "swapFrontBack" }; + ConfigWrapperLegacy sendFrontCanCmd {true, DoReset, {}, "sendFrontCanCmd" }; + ConfigWrapperLegacy sendBackCanCmd {true, DoReset, {}, "sendBackCanCmd" }; + ConfigWrapperLegacy canTransmitTimeout {200, DoReset, {}, "canTransmitTime" }; + ConfigWrapperLegacy canReceiveTimeout {0, DoReset, {}, "canReceiveTimeo" }; } controllerHardware; struct { - ConfigWrapper gametrakXMin {0, DoReset, {}, "gametrakXMin" }; - ConfigWrapper gametrakXMax {4095, DoReset, {}, "gametrakXMax" }; - ConfigWrapper gametrakYMin {0, DoReset, {}, "gametrakYMin" }; - ConfigWrapper gametrakYMax {4095, DoReset, {}, "gametrakYMax" }; - ConfigWrapper gametrakDistMin {0, DoReset, {}, "gametrakDistMin" }; - ConfigWrapper gametrakDistMax {4095, DoReset, {}, "gametrakDistMax" }; + ConfigWrapperLegacy gametrakXMin {0, DoReset, {}, "gametrakXMin" }; + ConfigWrapperLegacy gametrakXMax {4095, DoReset, {}, "gametrakXMax" }; + ConfigWrapperLegacy gametrakYMin {0, DoReset, {}, "gametrakYMin" }; + ConfigWrapperLegacy gametrakYMax {4095, DoReset, {}, "gametrakYMax" }; + ConfigWrapperLegacy gametrakDistMin {0, DoReset, {}, "gametrakDistMin" }; + ConfigWrapperLegacy gametrakDistMax {4095, DoReset, {}, "gametrakDistMax" }; struct { - ConfigWrapper statsUpdateRate{50, DoReset, {}, "statsUpdateRate" }; - ConfigWrapper cloudCollectRate{100, DoReset, {}, "cloudCollectRat" }; - ConfigWrapper cloudSendRate {1, DoReset, {}, "cloudSendRate" }; - ConfigWrapper udpSendRateMs {65, DoReset, {}, "udpSendRate" }; + ConfigWrapperLegacy statsUpdateRate{50, DoReset, {}, "statsUpdateRate" }; + ConfigWrapperLegacy cloudCollectRate{100, DoReset, {}, "cloudCollectRat" }; + ConfigWrapperLegacy cloudSendRate {1, DoReset, {}, "cloudSendRate" }; + ConfigWrapperLegacy udpSendRateMs {65, DoReset, {}, "udpSendRate" }; } timersSettings; } boardcomputerHardware; struct { - ConfigWrapper cloudEnabled {false, DoReset, {}, "cloudEnabled" }; - ConfigWrapper cloudTransmitTimeout{10, DoReset, {}, "clodTransmTmout" }; + ConfigWrapperLegacy cloudEnabled {false, DoReset, {}, "cloudEnabled" }; + ConfigWrapperLegacy cloudTransmitTimeout{10, DoReset, {}, "clodTransmTmout" }; } cloudSettings; struct { - ConfigWrapper udpUid {0, DoReset, {}, "cloudUDPUid" }; - ConfigWrapper udpCloudEnabled {false, DoReset, {}, "enUdpCloud" }; - ConfigWrapper enableCloudDebug {false, DoReset, {}, "debugCloud" }; - ConfigWrapper udpUseStdString {false, DoReset, {}, "udpusestdstr" }; + ConfigWrapperLegacy udpUid {0, DoReset, {}, "cloudUDPUid" }; + ConfigWrapperLegacy udpCloudEnabled {false, DoReset, {}, "enUdpCloud" }; + ConfigWrapperLegacy enableCloudDebug {false, DoReset, {}, "debugCloud" }; + ConfigWrapperLegacy udpUseStdString {false, DoReset, {}, "udpusestdstr" }; } udpCloudSettings; struct { - ConfigWrapper enableLedAnimation {true, DoReset, {}, "enableLedAnimat" }; - ConfigWrapper enableBrakeLights {true, DoReset, {}, "enableBrakeLigh" }; - ConfigWrapper ledsCount {288, DoReset, {}, "ledsCount" }; - ConfigWrapper centerOffset {1, DoReset, {}, "centerOffset" }; - ConfigWrapper smallOffset {4, DoReset, {}, "smallOffset" }; - ConfigWrapper bigOffset {10, DoReset, {}, "bigOffset" }; - ConfigWrapper enableBeepWhenBlink {true, DoReset, {}, "beepwhenblink" }; - ConfigWrapper animationType{LedstripAnimation::DefaultRainbow, DoReset, {}, "animationType" }; - ConfigWrapper enableFullBlink {true, DoReset, {}, "fullblink" }; - ConfigWrapper enableStVO {true, DoReset, {}, "ledstvo" }; - ConfigWrapper stvoFrontOffset {0, DoReset, {}, "ledstvofoff" }; - ConfigWrapper stvoFrontLength {10, DoReset, {}, "ledstvoflen" }; - ConfigWrapper stvoFrontEnable {false, DoReset, {}, "ledstvoen" }; - ConfigWrapper animationMultiplier{10, DoReset, {}, "ledAnimMul" }; - ConfigWrapper brightness {255, DoReset, {}, "ledbrightness" }; - ConfigWrapper enableAnimBlink {false, DoReset, {}, "enAnimBlink" }; - ConfigWrapper otaMode {OtaAnimationModes::GreenProgressBar, DoReset, {}, "ledOtaAnim" }; - ConfigWrapper maxMilliamps {3000, DoReset, {}, "ledMaxMilliamps" }; - ConfigWrapper enableVisualizeBlink {false, DoReset, {}, "enVisualBlink" }; - std::array, 8> custom_color { - ConfigWrapper {0, DoReset, {}, "ledCustomCol1" }, - ConfigWrapper {0, DoReset, {}, "ledCustomCol2" }, - ConfigWrapper {0, DoReset, {}, "ledCustomCol3" }, - ConfigWrapper {0, DoReset, {}, "ledCustomCol4" }, - ConfigWrapper {0, DoReset, {}, "ledCustomCol5" }, - ConfigWrapper {0, DoReset, {}, "ledCustomCol6" }, - ConfigWrapper {0, DoReset, {}, "ledCustomCol7" }, - ConfigWrapper {0, DoReset, {}, "ledCustomCol8" }, + ConfigWrapperLegacy enableLedAnimation {true, DoReset, {}, "enableLedAnimat" }; + ConfigWrapperLegacy enableBrakeLights {true, DoReset, {}, "enableBrakeLigh" }; + ConfigWrapperLegacy ledsCount {288, DoReset, {}, "ledsCount" }; + ConfigWrapperLegacy centerOffset {1, DoReset, {}, "centerOffset" }; + ConfigWrapperLegacy smallOffset {4, DoReset, {}, "smallOffset" }; + ConfigWrapperLegacy bigOffset {10, DoReset, {}, "bigOffset" }; + ConfigWrapperLegacy enableBeepWhenBlink {true, DoReset, {}, "beepwhenblink" }; + ConfigWrapperLegacy animationType{LedstripAnimation::DefaultRainbow, DoReset, {}, "animationType" }; + ConfigWrapperLegacy enableFullBlink {true, DoReset, {}, "fullblink" }; + ConfigWrapperLegacy enableStVO {true, DoReset, {}, "ledstvo" }; + ConfigWrapperLegacy stvoFrontOffset {0, DoReset, {}, "ledstvofoff" }; + ConfigWrapperLegacy stvoFrontLength {10, DoReset, {}, "ledstvoflen" }; + ConfigWrapperLegacy stvoFrontEnable {false, DoReset, {}, "ledstvoen" }; + ConfigWrapperLegacy animationMultiplier{10, DoReset, {}, "ledAnimMul" }; + ConfigWrapperLegacy brightness {255, DoReset, {}, "ledbrightness" }; + ConfigWrapperLegacy enableAnimBlink {false, DoReset, {}, "enAnimBlink" }; + ConfigWrapperLegacy otaMode {OtaAnimationModes::GreenProgressBar, DoReset, {}, "ledOtaAnim" }; + ConfigWrapperLegacy maxMilliamps {3000, DoReset, {}, "ledMaxMilliamps" }; + ConfigWrapperLegacy enableVisualizeBlink {false, DoReset, {}, "enVisualBlink" }; + std::array, 8> custom_color { + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol1" }, + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol2" }, + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol3" }, + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol4" }, + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol5" }, + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol6" }, + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol7" }, + ConfigWrapperLegacy {0, DoReset, {}, "ledCustomCol8" }, }; - ConfigWrapper leds_per_meter {144, DoReset, {}, "ledsPerMeter" }; - ConfigWrapper automaticLight {false, DoReset, {}, "nightLights" }; + ConfigWrapperLegacy leds_per_meter {144, DoReset, {}, "ledsPerMeter" }; + ConfigWrapperLegacy automaticLight {false, DoReset, {}, "nightLights" }; } ledstrip; struct { - ConfigWrapper cellsSeries {12, DoReset, {}, "batteryCS" }; - ConfigWrapper cellsParallel {10, DoReset, {}, "batteryCP" }; - ConfigWrapper cellType {BatteryCellType::_22P, DoReset, {}, "batteryType" }; - ConfigWrapper watthoursPerKilometer{25, DoReset, {}, "whkm" }; - ConfigWrapper front30VoltCalibration{3000, DoReset, {}, "batF30VCal" }; - ConfigWrapper back30VoltCalibration {3000, DoReset, {}, "batB30VCal" }; - ConfigWrapper front50VoltCalibration{5000, DoReset, {}, "batF50VCal" }; - ConfigWrapper back50VoltCalibration {5000, DoReset, {}, "batB50VCal" }; - ConfigWrapper applyCalibration {true, DoReset, {}, "applyBatCal" }; + ConfigWrapperLegacy cellsSeries {12, DoReset, {}, "batteryCS" }; + ConfigWrapperLegacy cellsParallel {10, DoReset, {}, "batteryCP" }; + ConfigWrapperLegacy cellType {BatteryCellType::_22P, DoReset, {}, "batteryType" }; + ConfigWrapperLegacy watthoursPerKilometer{25, DoReset, {}, "whkm" }; + ConfigWrapperLegacy front30VoltCalibration{3000, DoReset, {}, "batF30VCal" }; + ConfigWrapperLegacy back30VoltCalibration {3000, DoReset, {}, "batB30VCal" }; + ConfigWrapperLegacy front50VoltCalibration{5000, DoReset, {}, "batF50VCal" }; + ConfigWrapperLegacy back50VoltCalibration {5000, DoReset, {}, "batB50VCal" }; + ConfigWrapperLegacy applyCalibration {true, DoReset, {}, "applyBatCal" }; } battery; struct { - ConfigWrapper allowPresetSwitch {true, DoReset, {}, "lockAlwPresetSw" }; - ConfigWrapper keepLockedAfterReboot {false, DoReset, {}, "keepLocked" }; - ConfigWrapper locked {false, DoReset, {}, "currentlyLocked" }; - std::array, 4> pin { - ConfigWrapper {1, DoReset, MinMaxValue, "lockscreenPin0" }, - ConfigWrapper {2, DoReset, MinMaxValue, "lockscreenPin1" }, - ConfigWrapper {3, DoReset, MinMaxValue, "lockscreenPin2" }, - ConfigWrapper {4, DoReset, MinMaxValue, "lockscreenPin3" }, + ConfigWrapperLegacy allowPresetSwitch {true, DoReset, {}, "lockAlwPresetSw" }; + ConfigWrapperLegacy keepLockedAfterReboot {false, DoReset, {}, "keepLocked" }; + ConfigWrapperLegacy locked {false, DoReset, {}, "currentlyLocked" }; + std::array, 4> pin { + ConfigWrapperLegacy {1, DoReset, MinMaxValue, "lockscreenPin0" }, + ConfigWrapperLegacy {2, DoReset, MinMaxValue, "lockscreenPin1" }, + ConfigWrapperLegacy {3, DoReset, MinMaxValue, "lockscreenPin2" }, + ConfigWrapperLegacy {4, DoReset, MinMaxValue, "lockscreenPin3" }, }; - std::array, 4> pin2 { - ConfigWrapper {0, DoReset, MinMaxValue, "lockscrnPin1_0" }, - ConfigWrapper {0, DoReset, MinMaxValue, "lockscrnPin1_1" }, - ConfigWrapper {0, DoReset, MinMaxValue, "lockscrnPin1_2" }, - ConfigWrapper {0, DoReset, MinMaxValue, "lockscrnPin1_3" }, + std::array, 4> pin2 { + ConfigWrapperLegacy {0, DoReset, MinMaxValue, "lockscrnPin1_0" }, + ConfigWrapperLegacy {0, DoReset, MinMaxValue, "lockscrnPin1_1" }, + ConfigWrapperLegacy {0, DoReset, MinMaxValue, "lockscrnPin1_2" }, + ConfigWrapperLegacy {0, DoReset, MinMaxValue, "lockscrnPin1_3" }, }; } lockscreen; struct { - ConfigWrapper totalCentimeters {0, DoReset, {}, "totalCentimeter" }; + ConfigWrapperLegacy totalCentimeters {0, DoReset, {}, "totalCentimeter" }; } savedStatistics; struct { - ConfigWrapper mode {HandbremseMode::MOSFETS_OFF, DoReset, {}, "handBremsM" }; - ConfigWrapper triggerTimeout {10, DoReset, {}, "handBremsT" }; - ConfigWrapper automatic {false, DoReset, {}, "handBremsA" }; - ConfigWrapper enable {false, DoReset, {}, "handBremsE" }; - ConfigWrapper visualize {false, DoReset, {}, "handBremsV" }; + ConfigWrapperLegacy mode {HandbremseMode::MOSFETS_OFF, DoReset, {}, "handBremsM" }; + ConfigWrapperLegacy triggerTimeout {10, DoReset, {}, "handBremsT" }; + ConfigWrapperLegacy automatic {false, DoReset, {}, "handBremsA" }; + ConfigWrapperLegacy enable {false, DoReset, {}, "handBremsE" }; + ConfigWrapperLegacy visualize {false, DoReset, {}, "handBremsV" }; } handbremse; struct { - ConfigWrapper syncTime {false, DoReset, {}, "espnowSyncT" }; - ConfigWrapper syncTimeWithOthers {false, DoReset, {}, "espnowSyncTWO" }; - ConfigWrapper syncBlink {false, DoReset, {}, "espnowSyncBl" }; + ConfigWrapperLegacy syncTime {false, DoReset, {}, "espnowSyncT" }; + ConfigWrapperLegacy syncTimeWithOthers {false, DoReset, {}, "espnowSyncTWO" }; + ConfigWrapperLegacy syncBlink {false, DoReset, {}, "espnowSyncBl" }; } espnow; struct { @@ -368,10 +465,10 @@ public: ConfiguredFeatureFlag esp_now {"featureEspNow", false, false, "espnow"}; } feature; - ConfigWrapper anhaenger_id {0, DoReset, {}, "anhaenger_id" }; + ConfigWrapperLegacy anhaenger_id {0, DoReset, {}, "anhaenger_id" }; struct { - ConfigWrapper bleEnabled {true, DoReset, {}, "bleEnabled" }; + ConfigWrapperLegacy bleEnabled {true, DoReset, {}, "bleEnabled" }; } bleSettings; #define NEW_SETTINGS(x) \ diff --git a/main/ota.cpp b/main/ota.cpp index 9bae255..e982190 100644 --- a/main/ota.cpp +++ b/main/ota.cpp @@ -28,7 +28,7 @@ void handleOta() tl::expected triggerOta(std::string_view url) { - if (!configs.feature.ota.isEnabled.value) + if (!configs.feature.ota.isEnabled.value()) return tl::make_unexpected("OTA is not enabled!"); ESP_LOGI(TAG, "%.*s", url.size(), url.data()); diff --git a/main/potis.cpp b/main/potis.cpp index dcba266..a01e98a 100644 --- a/main/potis.cpp +++ b/main/potis.cpp @@ -30,7 +30,7 @@ void readPotis() constexpr auto sampleMultipleTimes = [](uint8_t pin){ analogRead(pin); double sum{}; - const auto sampleCount = configs.sampleCount.value; + const auto sampleCount = configs.sampleCount.value(); for (int i = 0; i < sampleCount; i++) sum += analogRead(pin); return sum / sampleCount; @@ -68,23 +68,23 @@ void readPotis() #ifndef FEATURE_JOYSTICK if (raw_gas) - gas = cpputils::mapValueClamped(*raw_gas, configs.gasMin.value, configs.gasMax.value, 0., 1000.); + gas = cpputils::mapValueClamped(*raw_gas, configs.gasMin.value(), configs.gasMax.value(), 0., 1000.); else gas = std::nullopt; if (raw_brems) - brems = cpputils::mapValueClamped(*raw_brems, configs.bremsMin.value, configs.bremsMax.value, 0., 1000.); + brems = cpputils::mapValueClamped(*raw_brems, configs.bremsMin.value(), configs.bremsMax.value(), 0., 1000.); else brems = std::nullopt; #else if (raw_gas) { - gas = map_analog_stick(configs.gasMitte.value, configs.gasMin.value, configs.gasMax.value, configs.deadband.value, *raw_gas); + gas = map_analog_stick(configs.gasMitte.value(), configs.gasMin.value(), configs.gasMax.value(), configs.deadband.value(), *raw_gas); } else gas = std::nullopt; if (raw_brems) { - brems = map_analog_stick(configs.bremsMitte.value, configs.bremsMin.value, configs.bremsMax.value, configs.deadband.value, *raw_brems); + brems = map_analog_stick(configs.bremsMitte.value(), configs.bremsMin.value(), configs.bremsMax.value(), configs.deadband.value(), *raw_brems); } else brems = std::nullopt; diff --git a/main/qrimport.cpp b/main/qrimport.cpp index 2be0763..d9adbe2 100644 --- a/main/qrimport.cpp +++ b/main/qrimport.cpp @@ -109,7 +109,7 @@ tl::expected start_qr_request() return tl::make_unexpected("request im oarsch"); } - if (auto res = http_request->start(fmt::format("http://qr.bobbycar.cloud/qr/{}.qr", configs.otaUsername.value)); !res) + if (auto res = http_request->start(fmt::format("http://qr.bobbycar.cloud/qr/{}.qr", configs.otaUsername.value())); !res) { return res; } diff --git a/main/screens.cpp b/main/screens.cpp index a8d94cd..c39dd98 100644 --- a/main/screens.cpp +++ b/main/screens.cpp @@ -20,7 +20,9 @@ void initScreen() tft.fillScreen(TFT_WHITE); tft.setTextColor(TFT_BLACK, TFT_WHITE); tft.setTextFont(4); + espgui::tft.setSwapBytes(true); tft.pushImage(0, 40, bobbyicons::logo.WIDTH, bobbyicons::logo.HEIGHT, bobbyicons::logo.buffer); + espgui::tft.setSwapBytes(false); tft.drawString("Bobbycar-OS", 32, 200); tft.drawString("booting...", 32, 225); tft.setTextFont(2); diff --git a/main/taskmanager.cpp b/main/taskmanager.cpp index 9dce9cf..cb91686 100644 --- a/main/taskmanager.cpp +++ b/main/taskmanager.cpp @@ -159,7 +159,7 @@ bool checkEnabledByName(std::string name) { // iterate over all feature flags (runForEveryFeature()) configs.callForEveryFeature([&](ConfiguredFeatureFlag &feature) { if (feature.getTaskName() == name) - enabled = feature.isEnabled.value; + enabled = feature.isEnabled.value(); }); return enabled; } diff --git a/main/time_bobbycar.cpp b/main/time_bobbycar.cpp index 307128b..0d66dab 100644 --- a/main/time_bobbycar.cpp +++ b/main/time_bobbycar.cpp @@ -17,7 +17,7 @@ espchrono::time_zone get_default_timezone() noexcept { using namespace espchrono; - return time_zone{configs.timezoneOffset.value, configs.timeDst.value}; + return time_zone{configs.timezoneOffset.value(), configs.timeDst.value()}; } #ifdef CONFIG_ESPCHRONO_SUPPORT_DEFAULT_TIMEZONE @@ -37,11 +37,11 @@ void initTime() { sntp_setoperatingmode(SNTP_OPMODE_POLL); static_assert(SNTP_MAX_SERVERS >= 1); - sntp_setservername(0, configs.timeServer.value.c_str()); + sntp_setservername(0, configs.timeServer.value().c_str()); sntp_set_time_sync_notification_cb(time_sync_notification_cb); - sntp_set_sync_mode(configs.timeSyncMode.value); - sntp_set_sync_interval(espchrono::milliseconds32{configs.timeSyncInterval.value}.count()); - if (configs.timeServerEnabled.value) + sntp_set_sync_mode(configs.timeSyncMode.value()); + sntp_set_sync_interval(espchrono::milliseconds32{configs.timeSyncInterval.value()}.count()); + if (configs.timeServerEnabled.value()) { ESP_LOGI("BOBBY", "sntp_init() ..."); sntp_init(); @@ -54,12 +54,12 @@ void initTime() void updateTime() { - if (!configs.feature.ntp.isEnabled.value) + if (!configs.feature.ntp.isEnabled.value()) return; - if (bool(sntp_enabled()) != configs.timeServerEnabled.value) + if (bool(sntp_enabled()) != configs.timeServerEnabled.value()) { - if (configs.timeServerEnabled.value) + if (configs.timeServerEnabled.value()) { ESP_LOGD("BOBBY", "calling sntp_init()..."); sntp_init(); @@ -73,24 +73,24 @@ void updateTime() } } - if (configs.timeServer.value != sntp_getservername(0)) + if (configs.timeServer.value() != sntp_getservername(0)) { - ESP_LOGD("BOBBY", "calling sntp_getservername() with %s...", configs.timeServer.value.c_str()); - sntp_setservername(0, configs.timeServer.value.c_str()); + ESP_LOGD("BOBBY", "calling sntp_getservername() with %s...", configs.timeServer.value().c_str()); + sntp_setservername(0, configs.timeServer.value().c_str()); ESP_LOGI("BOBBY", "sntp_getservername() finished"); } - if (configs.timeSyncMode.value != sntp_get_sync_mode()) + if (configs.timeSyncMode.value() != sntp_get_sync_mode()) { - ESP_LOGD("BOBBY", "calling sntp_set_sync_mode() with %s...", espcpputils::toString(configs.timeSyncMode.value).c_str()); - sntp_set_sync_mode(configs.timeSyncMode.value); + ESP_LOGD("BOBBY", "calling sntp_set_sync_mode() with %s...", espcpputils::toString(configs.timeSyncMode.value()).c_str()); + sntp_set_sync_mode(configs.timeSyncMode.value()); ESP_LOGI("BOBBY", "sntp_set_sync_mode() finished"); } - if (configs.timeSyncInterval.value != espchrono::milliseconds32{sntp_get_sync_interval()}) + if (configs.timeSyncInterval.value() != espchrono::milliseconds32{sntp_get_sync_interval()}) { - ESP_LOGD("BOBBY", "calling sntp_set_sync_interval() with %s...", espchrono::toString(configs.timeSyncInterval.value).c_str()); - sntp_set_sync_interval(espchrono::milliseconds32{configs.timeSyncInterval.value}.count()); + ESP_LOGD("BOBBY", "calling sntp_set_sync_interval() with %s...", espchrono::toString(configs.timeSyncInterval.value()).c_str()); + sntp_set_sync_interval(espchrono::milliseconds32{configs.timeSyncInterval.value()}.count()); ESP_LOGI("BOBBY", "sntp_set_sync_interval() finished"); } } diff --git a/main/udpcloud.cpp b/main/udpcloud.cpp index a201d53..799178f 100644 --- a/main/udpcloud.cpp +++ b/main/udpcloud.cpp @@ -39,10 +39,10 @@ void udpCloudInit() void udpCloudUpdate() { - if (!configs.feature.udpcloud.isEnabled.value) + if (!configs.feature.udpcloud.isEnabled.value()) return; - if (configs.udpCloudSettings.udpCloudEnabled.value && configs.udpCloudSettings.udpUid.touched()) + if (configs.udpCloudSettings.udpCloudEnabled.value() && configs.udpCloudSettings.udpUid.touched()) sendUdpCloudPacket(); } @@ -93,7 +93,7 @@ std::string buildUdpCloudJson() // const auto w_per_kmh = watt / avgSpeedKmh; // User ID - doc["uid"] = configs.udpCloudSettings.udpUid.value; + doc["uid"] = configs.udpCloudSettings.udpUid.value(); doc["upt"] = uptime; const auto addController = [&](const Controller &controller, const bool isBack) { @@ -143,7 +143,7 @@ std::string buildUdpCloudJson() // Statistics if(avgVoltage) { - doc["bP"] = getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value)); + doc["bP"] = getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value())); doc["bV"] = *avgVoltage; } doc["l"] = isLocked; @@ -153,7 +153,7 @@ std::string buildUdpCloudJson() doc["cW"] = watt; doc["wN"] = drivingStatistics.wh_used; doc["wL"] = getRemainingWattHours(); - doc["kmL"] = getRemainingWattHours() / configs.battery.watthoursPerKilometer.value; + doc["kmL"] = getRemainingWattHours() / configs.battery.watthoursPerKilometer.value(); doc["ver"] = version_string.substr(0, 6); serializeJson(doc, buf); @@ -190,8 +190,8 @@ std::string buildUdpCloudString() buf += "{"; // User ID - if(configs.udpCloudSettings.udpUid.value) - buf += fmt::format("\"uid\":{},", configs.udpCloudSettings.udpUid.value); + if(configs.udpCloudSettings.udpUid.value()) + buf += fmt::format("\"uid\":{},", configs.udpCloudSettings.udpUid.value()); else buf += "\"uid\":null,"; @@ -290,7 +290,7 @@ std::string buildUdpCloudString() // Statistics if(avgVoltage) { - buf += fmt::format("\"bP\":{},", getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value))); + buf += fmt::format("\"bP\":{},", getBatteryPercentage(*avgVoltage, BatteryCellType(configs.battery.cellType.value()))); buf += fmt::format("\"bV\":{},", *avgVoltage); } buf += fmt::format("\"l\":{},", isLocked); @@ -300,7 +300,7 @@ std::string buildUdpCloudString() buf += fmt::format("\"cW\":{},", watt); buf += fmt::format("\"wN\":{},", drivingStatistics.wh_used); buf += fmt::format("\"wL\":{},", getRemainingWattHours()); - buf += fmt::format("\"kmL\":{},", getRemainingWattHours() / configs.battery.watthoursPerKilometer.value); + buf += fmt::format("\"kmL\":{},", getRemainingWattHours() / configs.battery.watthoursPerKilometer.value()); buf += fmt::format("\"ver\":{}", version_string.substr(0, 6)); buf += "}"; @@ -310,14 +310,14 @@ std::string buildUdpCloudString() void sendUdpCloudPacket() { - EVERY_N_MILLIS(configs.boardcomputerHardware.timersSettings.udpSendRateMs.value) { + EVERY_N_MILLIS(configs.boardcomputerHardware.timersSettings.udpSendRateMs.value()) { if (espchrono::ago(timestampLastFailed) < 2s) { visualSendUdpPacket = false; return; } - if (configs.udpCloudHost.value.empty()) + if (configs.udpCloudHost.value().empty()) { visualSendUdpPacket = false; return; @@ -331,7 +331,7 @@ void sendUdpCloudPacket() ip_addr_t udpCloudIp; - if (const auto res = dns_gethostbyname(configs.udpCloudHost.value.c_str(), &udpCloudIp, nullptr, nullptr); res != ERR_OK) + if (const auto res = dns_gethostbyname(configs.udpCloudHost.value().c_str(), &udpCloudIp, nullptr, nullptr); res != ERR_OK) { if (res == ERR_INPROGRESS) { @@ -361,7 +361,7 @@ void sendUdpCloudPacket() wifi_stack::UdpSender udpCloudSender; std::string buf; - buf = configs.udpCloudSettings.udpUseStdString.value ? buildUdpCloudString() : buildUdpCloudJson(); + buf = configs.udpCloudSettings.udpUseStdString.value() ? buildUdpCloudString() : buildUdpCloudJson(); if (const auto result = udpCloudSender.send(receipient, buf); !result) diff --git a/main/utils.cpp b/main/utils.cpp index 0f3abdd..7b9bf57 100644 --- a/main/utils.cpp +++ b/main/utils.cpp @@ -12,12 +12,12 @@ espchrono::millis_clock::time_point lastReverseBeepToggle; float convertToKmh(float val) { - return val /* / profileSettings.controllerHardware.numMagnetPoles */ / 60.f * configs.controllerHardware.wheelDiameter.value / 1000.f * 3.14159265359f * 3.6f; + return val /* / profileSettings.controllerHardware.numMagnetPoles */ / 60.f * configs.controllerHardware.wheelDiameter.value() / 1000.f * 3.14159265359f * 3.6f; } float convertFromKmh(float val) { - return val /* * profileSettings.controllerHardware.numMagnetPoles */ * 60.f / configs.controllerHardware.wheelDiameter.value * 1000.f / 3.14159265359f / 3.6f; + return val /* * profileSettings.controllerHardware.numMagnetPoles */ * 60.f / configs.controllerHardware.wheelDiameter.value() * 1000.f / 3.14159265359f / 3.6f; } float convertToInch(float val) @@ -109,7 +109,7 @@ void fixCommonParams() motor.phaseAdvMax = profileSettings.limits.phaseAdvMax; } - if (configs.reverseBeep.value) + if (configs.reverseBeep.value()) { const auto x = motors(); const auto shouldBeep = std::all_of(std::begin(x), std::end(x), [](const bobbycar::protocol::serial::MotorState &motor){ return motor.pwm < 0; }); @@ -121,7 +121,7 @@ void fixCommonParams() reverseBeepToggle = true; lastReverseBeepToggle = espchrono::millis_clock::now(); for (auto &controller : controllers) - controller.command.buzzer = {.freq=configs.reverseBeepFreq0.value, .pattern=0}; + controller.command.buzzer = {.freq=configs.reverseBeepFreq0.value(), .pattern=0}; } else for (auto &controller : controllers) @@ -129,12 +129,12 @@ void fixCommonParams() currentlyReverseBeeping = shouldBeep; } - else if (shouldBeep && espchrono::millis_clock::now() - lastReverseBeepToggle >= std::chrono::milliseconds{reverseBeepToggle?configs.reverseBeepDuration0.value:configs.reverseBeepDuration1.value}) + else if (shouldBeep && espchrono::millis_clock::now() - lastReverseBeepToggle >= std::chrono::milliseconds{reverseBeepToggle?configs.reverseBeepDuration0.value():configs.reverseBeepDuration1.value()}) { reverseBeepToggle = !reverseBeepToggle; for (auto &controller : controllers) - controller.command.buzzer = {.freq=uint8_t(reverseBeepToggle?configs.reverseBeepFreq0.value:configs.reverseBeepFreq1.value), .pattern=0}; + controller.command.buzzer = {.freq=uint8_t(reverseBeepToggle?configs.reverseBeepFreq0.value():configs.reverseBeepFreq1.value()), .pattern=0}; lastReverseBeepToggle = espchrono::millis_clock::now(); } @@ -277,7 +277,7 @@ std::string local_clock_string() #ifdef CONFIG_ESPCHRONO_SUPPORT_DEFAULT_TIMEZONE const auto now = espchrono::local_clock::now(); #else // mir egal ob die lokalzeit richtig is - const auto now = espchrono::utc_clock::now() + configs.timezoneOffset.value; + const auto now = espchrono::utc_clock::now() + configs.timezoneOffset.value(); #endif const auto dt = espchrono::toDateTime(now); return fmt::format("{:02d}:{:02d}:{:02d}", dt.hour, dt.minute, dt.second); @@ -285,7 +285,7 @@ std::string local_clock_string() int16_t map_analog_stick(uint16_t middle, uint16_t start, uint16_t end, uint16_t deadband, uint16_t raw) { - if (abs(raw - middle) < configs.deadband.value) + if (abs(raw - middle) < configs.deadband.value()) { return 0; } @@ -294,15 +294,15 @@ int16_t map_analog_stick(uint16_t middle, uint16_t start, uint16_t end, uint16_t { if (raw < middle) { - raw += configs.deadband.value; - start += configs.deadband.value; + raw += configs.deadband.value(); + start += configs.deadband.value(); const auto return_val = cpputils::mapValueClamped(raw, start, middle, -1000, 0); return return_val; } else { - raw -= configs.deadband.value; - end -= configs.deadband.value; + raw -= configs.deadband.value(); + end -= configs.deadband.value(); const auto return_val = cpputils::mapValueClamped(raw, middle, end, 0, 1000); return return_val; } @@ -311,15 +311,15 @@ int16_t map_analog_stick(uint16_t middle, uint16_t start, uint16_t end, uint16_t { if (raw < middle) { - raw += configs.deadband.value; - end += configs.deadband.value; + raw += configs.deadband.value(); + end += configs.deadband.value(); const auto return_val = cpputils::mapValueClamped(raw, end, middle, 1000, 0); return return_val; } else { - raw -= configs.deadband.value; - start -= configs.deadband.value; + raw -= configs.deadband.value(); + start -= configs.deadband.value(); const auto return_val = cpputils::mapValueClamped(raw, middle, start, 0, -1000); return return_val; } diff --git a/main/webserver.cpp b/main/webserver.cpp index 98fe270..ac55ac6 100644 --- a/main/webserver.cpp +++ b/main/webserver.cpp @@ -44,7 +44,7 @@ esp_err_t webserver_status_handler(httpd_req_t *req); esp_err_t webserver_middleware_handler(httpd_req_t *req) { const auto handler = reinterpret_cast(req->user_ctx); - if (configs.feature.webserver_disable_lock.isEnabled.value) + if (configs.feature.webserver_disable_lock.isEnabled.value()) { return handler(req); } @@ -71,7 +71,7 @@ httpd_handle_t httpdHandle; void initWebserver() { - if(!configs.feature.webserver_disable_lock.isEnabled.value) + if(!configs.feature.webserver_disable_lock.isEnabled.value()) { webserver_lock.construct(); webserver_lock->take(portMAX_DELAY); @@ -117,7 +117,7 @@ void initWebserver() void handleWebserver() { - if (!configs.feature.webserver_disable_lock.isEnabled.value) + if (!configs.feature.webserver_disable_lock.isEnabled.value()) { webserver_lock->give(); vTaskDelay(1); @@ -197,7 +197,7 @@ esp_err_t webserver_status_handler(httpd_req_t *req) char tmpBuf[256]; const auto key_result = httpd_query_key_value(wants_json_query.data(), "json", tmpBuf, 256); - if (key_result == ESP_OK && (configs.webserverPassword.value.empty() || configs.webserverPassword.value == tmpBuf)) + if (key_result == ESP_OK && (configs.webserverPassword.value().empty() || configs.webserverPassword.value() == tmpBuf)) { if (!menuDisplayChanged()) { diff --git a/main/webserver_displaycontrol.cpp b/main/webserver_displaycontrol.cpp index bd92d52..89ec8bf 100644 --- a/main/webserver_displaycontrol.cpp +++ b/main/webserver_displaycontrol.cpp @@ -47,7 +47,7 @@ esp_err_t webserver_root_handler(httpd_req_t *req) char tmpBuf[256]; const auto key_result = httpd_query_key_value(wants_json_query.data(), "json", tmpBuf, 256); - if (key_result == ESP_OK && (configs.webserverPassword.value.empty() || configs.webserverPassword.value == tmpBuf)) + if (key_result == ESP_OK && (configs.webserverPassword.value().empty() || configs.webserverPassword.value() == tmpBuf)) { body += "{"; @@ -138,7 +138,7 @@ esp_err_t webserver_root_handler(httpd_req_t *req) body = body.erase(lastEckig+1, 1); } - else if (key_result != ESP_ERR_NOT_FOUND && tmpBuf != configs.webserverPassword.value) + else if (key_result != ESP_ERR_NOT_FOUND && tmpBuf != configs.webserverPassword.value()) { CALL_AND_EXIT(esphttpdutils::webserver_resp_send, req, esphttpdutils::ResponseStatus::Unauthorized, "text/plain", ""); } diff --git a/main/webserver_dumpnvs.cpp b/main/webserver_dumpnvs.cpp index 0eaa6e8..422663d 100644 --- a/main/webserver_dumpnvs.cpp +++ b/main/webserver_dumpnvs.cpp @@ -135,7 +135,7 @@ esp_err_t webserver_dump_nvs_handler(httpd_req_t *req) configs.callForEveryConfig([&](auto &config){ const std::string_view nvsName{config.nvsName()}; - showInputForSetting(nvsName, config.value, settings); + showInputForSetting(nvsName, config.value(), settings); }); const auto profile = settingsPersister.currentlyOpenProfileIndex(); diff --git a/main/webserver_newsettings.cpp b/main/webserver_newsettings.cpp index f88bc23..5c16399 100644 --- a/main/webserver_newsettings.cpp +++ b/main/webserver_newsettings.cpp @@ -334,7 +334,7 @@ esp_err_t webserver_newSettings_handler(httpd_req_t *req) { HtmlTag divTag{"div", "class=\"form-table-cell\"", body}; - showInputForSetting(nvsName, config.value, body); + showInputForSetting(nvsName, config.value(), body); } { diff --git a/main/webserver_ota.cpp b/main/webserver_ota.cpp index fa3038a..d40deb9 100644 --- a/main/webserver_ota.cpp +++ b/main/webserver_ota.cpp @@ -46,7 +46,7 @@ esp_err_t webserver_ota_percentage_handler(httpd_req_t *req) char tmpBuf[256]; const auto key_result = httpd_query_key_value(wants_json_query.data(), "json", tmpBuf, 256); - if (key_result == ESP_OK && (configs.webserverPassword.value.empty() || configs.webserverPassword.value == tmpBuf)) + if (key_result == ESP_OK && (configs.webserverPassword.value().empty() || configs.webserverPassword.value() == tmpBuf)) { body += "{"; if (asyncOta) @@ -63,7 +63,7 @@ esp_err_t webserver_ota_percentage_handler(httpd_req_t *req) body += "}"; } - else if (key_result != ESP_ERR_NOT_FOUND && configs.webserverPassword.value == tmpBuf) + else if (key_result != ESP_ERR_NOT_FOUND && configs.webserverPassword.value() == tmpBuf) { CALL_AND_EXIT(esphttpdutils::webserver_resp_send, req, esphttpdutils::ResponseStatus::Unauthorized, "text/plain", ""); } @@ -97,7 +97,7 @@ esp_err_t webserver_ota_handler(httpd_req_t *req) char tmpBuf[256]; const auto key_result = httpd_query_key_value(wants_json_query.data(), "json", tmpBuf, 256); - if (key_result == ESP_OK && (configs.webserverPassword.value.empty() || configs.webserverPassword.value == tmpBuf)) + if (key_result == ESP_OK && (configs.webserverPassword.value().empty() || configs.webserverPassword.value() == tmpBuf)) { body += "{"; @@ -157,7 +157,7 @@ esp_err_t webserver_ota_handler(httpd_req_t *req) if (std::string::npos != lastEckig) body = body.erase(lastEckig+1, 1); } - else if (key_result != ESP_ERR_NOT_FOUND && configs.webserverPassword.value == tmpBuf) + else if (key_result != ESP_ERR_NOT_FOUND && configs.webserverPassword.value() == tmpBuf) { CALL_AND_EXIT(esphttpdutils::webserver_resp_send, req, esphttpdutils::ResponseStatus::Unauthorized, "text/plain", ""); @@ -325,7 +325,7 @@ esp_err_t webserver_ota_handler(httpd_req_t *req) body += "Trigger Update"; } - body += fmt::format("", esphttpdutils::htmlentities(configs.otaUrl.value)); + body += fmt::format("", esphttpdutils::htmlentities(configs.otaUrl.value())); { HtmlTag buttonTag{"button", "type=\"submit\"", body}; diff --git a/main/wifi_bobbycar.cpp b/main/wifi_bobbycar.cpp index 6124f37..91d3563 100644 --- a/main/wifi_bobbycar.cpp +++ b/main/wifi_bobbycar.cpp @@ -51,7 +51,7 @@ namespace { wifi_stack::config createConfig() { return wifi_stack::config { - .base_mac_override = configs.baseMacAddressOverride.value, + .base_mac_override = configs.baseMacAddressOverride.value(), //.dual_ant = dual_ant_config{}, .sta = createStaConfig(), .ap = createApConfig(), @@ -63,11 +63,11 @@ wifi_stack::config createConfig() std::optional createStaConfig() { - if (!configs.wifiStaEnabled.value) + if (!configs.wifiStaEnabled.value()) return std::nullopt; return wifi_stack::sta_config{ - .hostname = configs.hostname.value, + .hostname = configs.hostname.value(), .wifis = std::array { createWifiEntry(configs.wifi_configs[0]), createWifiEntry(configs.wifi_configs[1]), @@ -80,7 +80,7 @@ std::optional createStaConfig() createWifiEntry(configs.wifi_configs[8]), createWifiEntry(configs.wifi_configs[9]) }, - .min_rssi = configs.wifiStaMinRssi.value, + .min_rssi = configs.wifiStaMinRssi.value(), .long_range = false }; } @@ -88,27 +88,27 @@ std::optional createStaConfig() wifi_stack::wifi_entry createWifiEntry(const WiFiConfig &wifi_config) { std::optional static_ip; - if (wifi_config.useStaticIp.value) + if (wifi_config.useStaticIp.value()) static_ip = wifi_stack::static_ip_config { - .ip = wifi_config.staticIp.value, - .subnet = wifi_config.staticSubnet.value, - .gateway = wifi_config.staticGateway.value + .ip = wifi_config.staticIp.value(), + .subnet = wifi_config.staticSubnet.value(), + .gateway = wifi_config.staticGateway.value() }; wifi_stack::static_dns_config static_dns; - if (wifi_config.useStaticDns.value) + if (wifi_config.useStaticDns.value()) { - if (wifi_config.staticDns0.value.value()) - static_dns.main = wifi_config.staticDns0.value; - if (wifi_config.staticDns1.value.value()) - static_dns.backup = wifi_config.staticDns1.value; - if (wifi_config.staticDns2.value.value()) - static_dns.fallback = wifi_config.staticDns2.value; + if (wifi_config.staticDns0.value().value()) + static_dns.main = wifi_config.staticDns0.value(); + if (wifi_config.staticDns1.value().value()) + static_dns.backup = wifi_config.staticDns1.value(); + if (wifi_config.staticDns2.value().value()) + static_dns.fallback = wifi_config.staticDns2.value(); } return wifi_stack::wifi_entry { - .ssid = wifi_config.ssid.value, - .key = wifi_config.key.value, + .ssid = wifi_config.ssid.value(), + .key = wifi_config.key.value(), .static_ip = static_ip, .static_dns = static_dns }; @@ -116,7 +116,7 @@ wifi_stack::wifi_entry createWifiEntry(const WiFiConfig &wifi_config) std::optional createApConfig() { - if (!configs.wifiApEnabled.value) + if (!configs.wifiApEnabled.value()) return std::nullopt; // if (configs.wifiDisableApWhenOnline.value && @@ -127,16 +127,16 @@ std::optional createApConfig() // return std::nullopt; return wifi_stack::ap_config { - .hostname = configs.hostname.value, - .ssid = configs.wifiApName.value, - .key = configs.wifiApKey.value, + .hostname = configs.hostname.value(), + .ssid = configs.wifiApName.value(), + .key = configs.wifiApKey.value(), .static_ip = { - .ip = configs.wifiApIp.value, - .subnet = configs.wifiApMask.value, - .gateway = configs.wifiApIp.value, + .ip = configs.wifiApIp.value(), + .subnet = configs.wifiApMask.value(), + .gateway = configs.wifiApIp.value(), }, - .channel = configs.wifiApChannel.value, - .authmode = configs.wifiApAuthmode.value, + .channel = configs.wifiApChannel.value(), + .authmode = configs.wifiApAuthmode.value(), .ssid_hidden = false, .max_connection = 4, .beacon_interval = 100, diff --git a/sdkconfig_allfeatures b/sdkconfig_allfeatures index 760a869..90b371a 100644 --- a/sdkconfig_allfeatures +++ b/sdkconfig_allfeatures @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -816,6 +813,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -980,37 +981,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1417,6 +1387,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1592,6 +1566,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1688,12 +1663,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1704,6 +1673,15 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION=y # CONFIG_ESP32_PHY_DEFAULT_INIT_IF_INVALID is not set @@ -1712,6 +1690,10 @@ CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1762,19 +1744,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1801,6 +1770,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_comred b/sdkconfig_comred index b514eea..1c9c131 100644 --- a/sdkconfig_comred +++ b/sdkconfig_comred @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -814,6 +811,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -978,37 +979,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1415,6 +1385,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1590,6 +1564,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1686,12 +1661,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1702,12 +1671,25 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1758,19 +1740,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1797,6 +1766,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_comred_new b/sdkconfig_comred_new index b514eea..1c9c131 100644 --- a/sdkconfig_comred_new +++ b/sdkconfig_comred_new @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -814,6 +811,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -978,37 +979,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1415,6 +1385,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1590,6 +1564,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1686,12 +1661,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1702,12 +1671,25 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1758,19 +1740,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1797,6 +1766,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_feedc0de b/sdkconfig_feedc0de index 760a869..90b371a 100644 --- a/sdkconfig_feedc0de +++ b/sdkconfig_feedc0de @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -816,6 +813,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -980,37 +981,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1417,6 +1387,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1592,6 +1566,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1688,12 +1663,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1704,6 +1673,15 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION=y # CONFIG_ESP32_PHY_DEFAULT_INIT_IF_INVALID is not set @@ -1712,6 +1690,10 @@ CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1762,19 +1744,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1801,6 +1770,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_gernot b/sdkconfig_gernot index b514eea..1c9c131 100644 --- a/sdkconfig_gernot +++ b/sdkconfig_gernot @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -814,6 +811,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -978,37 +979,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1415,6 +1385,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1590,6 +1564,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1686,12 +1661,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1702,12 +1671,25 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1758,19 +1740,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1797,6 +1766,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_greyhash b/sdkconfig_greyhash index aa62d92..abb0d14 100644 --- a/sdkconfig_greyhash +++ b/sdkconfig_greyhash @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_160=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_240 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=160 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -814,6 +811,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160=y +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=160 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -978,37 +979,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1415,6 +1385,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1590,6 +1564,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1686,12 +1661,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1702,12 +1671,25 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_160=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_240 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=160 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1758,19 +1740,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1797,6 +1766,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_mick b/sdkconfig_mick index aa62d92..abb0d14 100644 --- a/sdkconfig_mick +++ b/sdkconfig_mick @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_160=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_240 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=160 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -814,6 +811,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160=y +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=160 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -978,37 +979,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1415,6 +1385,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1590,6 +1564,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1686,12 +1661,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1702,12 +1671,25 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_160=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_240 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=160 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1758,19 +1740,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1797,6 +1766,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_nofeatures b/sdkconfig_nofeatures index 5e67e26..c1b8907 100644 --- a/sdkconfig_nofeatures +++ b/sdkconfig_nofeatures @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -816,6 +813,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -980,37 +981,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1417,6 +1387,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1592,6 +1566,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1688,12 +1663,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1704,6 +1673,15 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION=y # CONFIG_ESP32_PHY_DEFAULT_INIT_IF_INVALID is not set @@ -1712,6 +1690,10 @@ CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1762,19 +1744,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1801,6 +1770,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_peter b/sdkconfig_peter index b514eea..1c9c131 100644 --- a/sdkconfig_peter +++ b/sdkconfig_peter @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -814,6 +811,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -978,37 +979,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1415,6 +1385,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1590,6 +1564,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1686,12 +1661,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1702,12 +1671,25 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1758,19 +1740,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1797,6 +1766,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/sdkconfig_seatbot b/sdkconfig_seatbot index b514eea..1c9c131 100644 --- a/sdkconfig_seatbot +++ b/sdkconfig_seatbot @@ -78,6 +78,7 @@ CONFIG_SOC_LCD_I80_SUPPORTED=y CONFIG_SOC_LCD_I80_BUSES=2 CONFIG_SOC_LCD_I80_BUS_WIDTH=24 CONFIG_SOC_LEDC_HAS_TIMER_SPECIFIC_MUX=y +CONFIG_SOC_LEDC_SUPPORT_APB_CLOCK=y CONFIG_SOC_LEDC_SUPPORT_REF_TICK=y CONFIG_SOC_LEDC_SUPPORT_HS_MODE=y CONFIG_SOC_LEDC_CHANNEL_NUM=8 @@ -105,6 +106,7 @@ CONFIG_SOC_RMT_RX_CANDIDATES_PER_GROUP=8 CONFIG_SOC_RMT_CHANNELS_PER_GROUP=8 CONFIG_SOC_RMT_MEM_WORDS_PER_CHANNEL=64 CONFIG_SOC_RMT_SUPPORT_REF_TICK=y +CONFIG_SOC_RMT_SUPPORT_APB=y CONFIG_SOC_RMT_CHANNEL_CLK_INDEPENDENT=y CONFIG_SOC_RTCIO_PIN_COUNT=18 CONFIG_SOC_RTCIO_INPUT_OUTPUT_SUPPORTED=y @@ -122,6 +124,7 @@ CONFIG_SOC_TIMER_GROUPS=2 CONFIG_SOC_TIMER_GROUP_TIMERS_PER_GROUP=2 CONFIG_SOC_TIMER_GROUP_COUNTER_BIT_WIDTH=64 CONFIG_SOC_TIMER_GROUP_TOTAL_TIMERS=4 +CONFIG_SOC_TIMER_GROUP_SUPPORT_APB=y CONFIG_SOC_TOUCH_VERSION_1=y CONFIG_SOC_TOUCH_SENSOR_NUM=10 CONFIG_SOC_TOUCH_PAD_MEASURE_WAIT_MAX=0xFF @@ -365,6 +368,7 @@ CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_INFO=y # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_DEBUG is not set # CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK_VERBOSE is not set CONFIG_LOG_LOCAL_LEVEL_WIFI_STACK=3 +# CONFIG_WIFI_DUAL_ANT is not set # end of ESP WiFi Stack settings # @@ -636,28 +640,10 @@ CONFIG_ESP_TLS_USING_MBEDTLS=y # # ESP32-specific # -CONFIG_ESP32_REV_MIN_0=y -# CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_2 is not set -# CONFIG_ESP32_REV_MIN_3 is not set -CONFIG_ESP32_REV_MIN=0 CONFIG_ESP32_DPORT_WORKAROUND=y -# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set -# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set -CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y -CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_SPIRAM_SUPPORT is not set # CONFIG_ESP32_TRAX is not set CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y -# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set -# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set -CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y -# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set -# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set -# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set -CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 CONFIG_ESP32_XTAL_FREQ_40=y # CONFIG_ESP32_XTAL_FREQ_26 is not set @@ -765,6 +751,11 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # RTC Clock Config # +CONFIG_RTC_CLK_SRC_INT_RC=y +# CONFIG_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_RTC_CLK_CAL_CYCLES=1024 # end of RTC Clock Config # @@ -772,6 +763,12 @@ CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # # CONFIG_PERIPH_CTRL_FUNC_IN_IRAM is not set # end of Peripheral Control + +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 # end of Hardware Settings # @@ -814,6 +811,10 @@ CONFIG_ESP_PHY_REDUCE_TX_POWER=y # # ESP System Settings # +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_80 is not set +# CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_160 is not set +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y # CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set @@ -978,37 +979,6 @@ CONFIG_FATFS_PER_FILE_CACHE=y # CONFIG_FATFS_USE_FASTSEEK is not set # end of FAT Filesystem support -# -# Modbus configuration -# -CONFIG_FMB_COMM_MODE_TCP_EN=y -CONFIG_FMB_TCP_PORT_DEFAULT=502 -CONFIG_FMB_TCP_PORT_MAX_CONN=5 -CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 -CONFIG_FMB_COMM_MODE_RTU_EN=y -CONFIG_FMB_COMM_MODE_ASCII_EN=y -CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_FMB_QUEUE_LENGTH=20 -CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 -CONFIG_FMB_SERIAL_BUF_SIZE=256 -CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 -CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 -CONFIG_FMB_PORT_TASK_PRIO=10 -# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set -CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y -# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set -CONFIG_FMB_PORT_TASK_AFFINITY=0x0 -CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_FMB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 -CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_FMB_TIMER_PORT_ENABLED=y -# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set -# end of Modbus configuration - # # FreeRTOS # @@ -1415,6 +1385,10 @@ CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y # CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # CONFIG_NEWLIB_NANO_FORMAT is not set +CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC_HRT=y +# CONFIG_NEWLIB_TIME_SYSCALL_USE_RTC is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_HRT is not set +# CONFIG_NEWLIB_TIME_SYSCALL_USE_NONE is not set # end of Newlib # @@ -1590,6 +1564,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y # Deprecated options for backward compatibility # CONFIG_NO_BLOBS is not set +# CONFIG_ESP32_NO_BLOBS is not set # CONFIG_LOG_BOOTLOADER_LEVEL_NONE is not set # CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set # CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set @@ -1686,12 +1661,6 @@ CONFIG_NIMBLE_CRYPTO_STACK_MBEDTLS=y CONFIG_ADC2_DISABLE_DAC=y # CONFIG_SPIRAM_SUPPORT is not set CONFIG_TRACEMEM_RESERVE_DRAM=0x0 -CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y -# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set -CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set -# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set # CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set # CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set # CONFIG_EVENT_LOOP_PROFILING is not set @@ -1702,12 +1671,25 @@ CONFIG_OTA_ALLOW_HTTP=y CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 CONFIG_ESP_SYSTEM_PD_FLASH=y +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP32_PHY_MAX_TX_POWER=20 CONFIG_REDUCE_PHY_TX_POWER=y CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=240 # CONFIG_ESP32_PANIC_PRINT_HALT is not set CONFIG_ESP32_PANIC_PRINT_REBOOT=y # CONFIG_ESP32_PANIC_SILENT_REBOOT is not set @@ -1758,19 +1740,6 @@ CONFIG_SW_COEXIST_ENABLE=y # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set # CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y -CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 -CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 -CONFIG_MB_QUEUE_LENGTH=20 -CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 -CONFIG_MB_SERIAL_BUF_SIZE=256 -CONFIG_MB_SERIAL_TASK_PRIO=10 -CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT=y -CONFIG_MB_CONTROLLER_SLAVE_ID=0x00112233 -CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 -CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 -CONFIG_MB_CONTROLLER_STACK_SIZE=4096 -CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 -CONFIG_MB_TIMER_PORT_ENABLED=y # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 @@ -1797,6 +1766,12 @@ CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y # CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF # CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_HRT=y +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_HRT is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072 CONFIG_ESP32_PTHREAD_STACK_MIN=768 diff --git a/set_submod_branches.sh b/set_submod_branches.sh new file mode 100755 index 0000000..5917e8b --- /dev/null +++ b/set_submod_branches.sh @@ -0,0 +1,26 @@ +#!/bin/bash + +( pushd esp-idf ; git checkout fixes ; git pull ) & +( pushd esp-protocols ; git checkout fixes ; git pull ) & +( pushd components/arduino-esp32 ; git checkout remove-lowquality-parts ; git pull ) & +( pushd components/ArduinoJson ; git checkout esp-idf-refactoring ; git pull ) & +( pushd components/bobbycar-protocol ; git checkout master ; git pull ) & +( pushd components/cpputils ; git checkout main ; git pull ) & +( pushd components/cxx-ring-buffer ; git checkout esp-idf ; git pull ) & +( pushd components/date ; git checkout esp-idf-refactoring ; git pull ) & +( pushd components/esp-gui-lib ; git checkout main ; git pull ) & +( pushd components/esp-nimble-cpp ; git checkout remove-arduino-bullshit ; git pull ) & +( pushd components/espasynchttpreq ; git checkout master ; git pull ) & +( pushd components/espasyncota ; git checkout main ; git pull ) & +( pushd components/espchrono ; git checkout main ; git pull ) & +( pushd components/espconfiglib ; git checkout main ; git pull ) & +( pushd components/espcpputils ; git checkout main ; git pull ) & +( pushd components/esphttpdutils ; git checkout main ; git pull ) & +( pushd components/espwifistack ; git checkout main ; git pull ) & +( pushd components/expected ; git checkout esp-idf-fixes ; git pull ) & +( pushd components/FastLED-idf ; git checkout fixes ; git pull ) & +( pushd components/fmt ; git checkout esp-idf-rewrite ; git pull ) & +( pushd components/QRCode-esp32 ; git checkout fixes ; git pull ) & +( pushd components/sunset ; git checkout fixes ; git pull ) & +( pushd components/TFT_eSPI ; git checkout esp-idf-fixes ; git pull ) & +wait diff --git a/update_all_sdkconfigs.py b/update_all_sdkconfigs.py new file mode 100755 index 0000000..3dfadda --- /dev/null +++ b/update_all_sdkconfigs.py @@ -0,0 +1,28 @@ +#!/usr/bin/env python3 +import os +import subprocess + +# execute './switchconf.sh --list' to get the list of available configurations +output = subprocess.check_output(['bash', './switchconf.sh', '--list']).decode('utf-8').splitlines() + +# read symlink './sdkconfig' to get the current configuration +current_config = os.readlink('./sdkconfig') + +if len(output) == 0: + print('No configurations found!') + exit(1) + +# check if PATH (env) contains 'bobbycar-boardcomputer-firmware +if 'bobbycar-boardcomputer-firmware' not in os.environ['PATH']: + print('Please execute ". export.sh"') + exit(1) + +for config in output: + print('Switching to configuration: ' + config) + subprocess.check_call(['bash', './switchconf.sh', config]) + # execute idf.py menuconfig and wait for user to close again + subprocess.check_call(['idf.py', 'menuconfig']) + +# switch back to current configuration +print('Switching back to configuration: ' + current_config) +subprocess.check_call(['bash', './switchconf.sh', current_config]) \ No newline at end of file