diff --git a/FluidNC/esp32/StartupLog.cpp b/FluidNC/esp32/StartupLog.cpp new file mode 100644 index 000000000..034e10d2b --- /dev/null +++ b/FluidNC/esp32/StartupLog.cpp @@ -0,0 +1,52 @@ +// Copyright (c) 2023 - Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#include "src/StartupLog.h" +#include "src/Protocol.h" // send_line() +#include + +// The startup log is stored in RTC RAM that is preserved across +// resets. That lets us show the previous startup log if the +// system panics and resets. + +// The size is limited by the size of RTC RAM minus system usage thereof +static const size_t _maxlen = 7000; +static RTC_NOINIT_ATTR char _messages[_maxlen]; +static RTC_NOINIT_ATTR size_t _len; +static bool _paniced; + +void StartupLog::init() { + if (esp_reset_reason() == ESP_RST_PANIC) { + _paniced = true; + } else { + _paniced = false; + _len = 0; + } +} +size_t StartupLog::write(uint8_t data) { + if (_paniced || _len >= _maxlen) { + return 0; + } + _messages[_len++] = (char)data; + return 1; +} +void StartupLog::dump(Channel& out) { + if (_paniced) { + log_error_to(out, "Showing startup log from previous panic"); + } + for (size_t i = 0; i < _len;) { + std::string line; + while (i < _len) { + char c = _messages[i++]; + if (c == '\n') { + break; + } + line += c; + } + log_to(out, line); + } +} + +StartupLog::~StartupLog() {} + +StartupLog startupLog; diff --git a/FluidNC/src/CoolantControl.cpp b/FluidNC/src/CoolantControl.cpp index 7daa6d1a1..38583f108 100644 --- a/FluidNC/src/CoolantControl.cpp +++ b/FluidNC/src/CoolantControl.cpp @@ -53,6 +53,8 @@ void CoolantControl::write(CoolantState state) { bool pinState = state.Mist; _mist.synchronousWrite(pinState); } + + _previous_state = state; } // Directly called by coolant_init(), coolant_set_state(), which can be at @@ -68,11 +70,13 @@ void CoolantControl::stop() { // parser program end, and g-code parser CoolantControl::sync(). void CoolantControl::set_state(CoolantState state) { - if (sys.abort) { - return; // Block during abort. + if (sys.abort || (_previous_state.Mist == state.Mist && _previous_state.Flood == state.Flood)) { + return; // Block during abort or if no change } write(state); - delay_msec(_delay_ms, DwellMode::SysSuspend); + + if (state.Mist || state.Flood) // ignore delay on turn off + delay_msec(_delay_ms, DwellMode::SysSuspend); } void CoolantControl::off() { diff --git a/FluidNC/src/CoolantControl.h b/FluidNC/src/CoolantControl.h index 4726e4fb0..c4c368947 100644 --- a/FluidNC/src/CoolantControl.h +++ b/FluidNC/src/CoolantControl.h @@ -13,6 +13,8 @@ class CoolantControl : public Configuration::Configurable { uint32_t _delay_ms = 0; + CoolantState _previous_state = {}; + void write(CoolantState state); public: diff --git a/FluidNC/src/Error.cpp b/FluidNC/src/Error.cpp index 45de5ab93..7722f3d2c 100644 --- a/FluidNC/src/Error.cpp +++ b/FluidNC/src/Error.cpp @@ -68,7 +68,6 @@ std::map ErrorNames = { { Error::AuthenticationFailed, "Authentication failed!" }, { Error::Eol, "End of line" }, { Error::Eof, "End of file" }, - { Error::Reset, "System Reset" }, { Error::AnotherInterfaceBusy, "Another interface is busy" }, { Error::BadPinSpecification, "Bad Pin Specification" }, { Error::JogCancelled, "Jog Cancelled" }, diff --git a/FluidNC/src/Error.h b/FluidNC/src/Error.h index 590c5a816..a8387b25e 100644 --- a/FluidNC/src/Error.h +++ b/FluidNC/src/Error.h @@ -72,7 +72,6 @@ enum class Error : uint8_t { AuthenticationFailed = 110, Eol = 111, Eof = 112, // Not necessarily an error - Reset = 113, AnotherInterfaceBusy = 120, JogCancelled = 130, BadPinSpecification = 150, diff --git a/FluidNC/src/GCode.cpp b/FluidNC/src/GCode.cpp index 1ea5e722a..3d74db282 100644 --- a/FluidNC/src/GCode.cpp +++ b/FluidNC/src/GCode.cpp @@ -1620,9 +1620,6 @@ Error gc_execute_line(char* line) { // As far as the parser is concerned, the position is now == target. In reality the // motion control system might still be processing the action and the real tool position // in any intermediate location. - if (sys.abort) { - return Error::Reset; - } if (gc_update_pos == GCUpdatePos::Target) { copyAxes(gc_state.position, gc_block.values.xyz); } else if (gc_update_pos == GCUpdatePos::System) { diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index 170030ddb..21f461066 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -66,6 +66,7 @@ namespace Machine { handler.section("user_outputs", _userOutputs); handler.section("oled", _oled); + handler.section("status_outputs", _stat_out); Spindles::SpindleFactory::factory(handler, _spindles); diff --git a/FluidNC/src/Machine/MachineConfig.h b/FluidNC/src/Machine/MachineConfig.h index 9541141bc..9f33ae328 100644 --- a/FluidNC/src/Machine/MachineConfig.h +++ b/FluidNC/src/Machine/MachineConfig.h @@ -20,6 +20,7 @@ #include "../Stepper.h" #include "../Config.h" #include "../OLED.h" +#include "../Status_outputs.h" #include "Axes.h" #include "SPIBus.h" #include "I2CBus.h" @@ -74,6 +75,7 @@ namespace Machine { Start* _start = nullptr; Parking* _parking = nullptr; OLED* _oled = nullptr; + Status_Outputs* _stat_out = nullptr; Spindles::SpindleList _spindles; UartChannel* _uart_channels[MAX_N_UARTS] = { nullptr }; diff --git a/FluidNC/src/Machine/Macros.cpp b/FluidNC/src/Machine/Macros.cpp index 2284ae0d0..f58379e73 100644 --- a/FluidNC/src/Machine/Macros.cpp +++ b/FluidNC/src/Machine/Macros.cpp @@ -6,17 +6,20 @@ #include "src/System.h" // sys #include "src/Machine/MachineConfig.h" // config -Macro::Macro(const char* name) : _name(name) {} - void MacroEvent::run(void* arg) { - config->_macros->_macro[_num].run(); + int n = int(arg); + if (sys.state != State::Idle) { + log_error("Macro can only be used in idle state"); + return; + } + config->_macros->_macro[n].run(); } -Macro Macros::_startup_line[n_startup_lines] = { "startup_line0", "startup_line1" }; -Macro Macros::_macro[n_macros] = { "macro0", "macro1", "macro2", "macro3", "macro4" }; -Macro Macros::_after_homing { "after_homing" }; -Macro Macros::_after_reset { "after_reset" }; -Macro Macros::_after_unlock { "after_unlock" }; +Macro Macros::_startup_line[n_startup_lines] = { { "startup_line0" }, { "startup_line1" } }; +Macro Macros::_macro[n_macros] = { { "macro0" }, { "macro1" }, { "macro2" }, { "macro3" } }; +Macro Macros::_after_homing = { "after_homing" }; +Macro Macros::_after_reset = { "after_reset" }; +Macro Macros::_after_unlock = { "after_unlock" }; MacroEvent macro0Event { 0 }; MacroEvent macro1Event { 1 }; @@ -51,11 +54,6 @@ Cmd findOverride(std::string name) { } bool Macro::run() { - if (sys.state != State::Idle) { - log_error("Macro can only be used in idle state"); - return false; - } - const std::string& s = _gcode; if (_gcode == "") { return true; diff --git a/FluidNC/src/Machine/Macros.h b/FluidNC/src/Machine/Macros.h index ec117fa1e..a462bc0c6 100644 --- a/FluidNC/src/Machine/Macros.h +++ b/FluidNC/src/Machine/Macros.h @@ -27,15 +27,15 @@ namespace Machine { class Macro { public: std::string _gcode; - const char* _name; - Macro(const char* name); + std::string _name; + Macro(const char* name) : _name(name) {} bool run(); }; class Macros : public Configuration::Configurable { public: static const int n_startup_lines = 2; - static const int n_macros = 5; + static const int n_macros = 4; static Macro _macro[n_macros]; static Macro _startup_line[n_startup_lines]; @@ -50,15 +50,15 @@ namespace Machine { // TODO: We could validate the startup lines void group(Configuration::HandlerBase& handler) override { - handler.item(_startup_line[0]._name, _startup_line[0]._gcode); - handler.item(_startup_line[1]._name, _startup_line[1]._gcode); - handler.item(_macro[0]._name, _macro[0]._gcode); - handler.item(_macro[1]._name, _macro[1]._gcode); - handler.item(_macro[2]._name, _macro[2]._gcode); - handler.item(_macro[3]._name, _macro[3]._gcode); - handler.item(_after_homing._name, _after_homing._gcode); - handler.item(_after_reset._name, _after_reset._gcode); - handler.item(_after_unlock._name, _after_unlock._gcode); + handler.item(_startup_line[0]._name.c_str(), _startup_line[0]._gcode); + handler.item(_startup_line[1]._name.c_str(), _startup_line[1]._gcode); + handler.item(_macro[0]._name.c_str(), _macro[0]._gcode); + handler.item(_macro[1]._name.c_str(), _macro[1]._gcode); + handler.item(_macro[2]._name.c_str(), _macro[2]._gcode); + handler.item(_macro[3]._name.c_str(), _macro[3]._gcode); + handler.item(_after_homing._name.c_str(), _after_homing._gcode); + handler.item(_after_reset._name.c_str(), _after_reset._gcode); + handler.item(_after_unlock._name.c_str(), _after_unlock._gcode); } ~Macros() {} diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 6da6ed47e..3c8b5513c 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -34,6 +34,8 @@ void setup() { uartInit(); // Setup serial port Uart0.println(); // create some white space after ESP32 boot info + StartupLog::init(); + // Setup input polling loop after loading the configuration, // because the polling may depend on the config allChannels.init(); @@ -47,7 +49,7 @@ void setup() { // Load settings from non-volatile storage settings_init(); // requires config - log_info("FluidNC " << git_info); + log_info("FluidNC " << git_info << " " << git_url); log_info("Compiled with ESP32 SDK:" << esp_get_idf_version()); if (localfs_mount()) { @@ -96,6 +98,10 @@ void setup() { config->_oled->init(); } + if (config->_stat_out) { + config->_stat_out->init(); + } + config->_stepping->init(); // Configure stepper interrupt timers plan_init(); diff --git a/FluidNC/src/Motors/TrinamicUartDriver.cpp b/FluidNC/src/Motors/TrinamicUartDriver.cpp index 369bb126d..97ac24729 100644 --- a/FluidNC/src/Motors/TrinamicUartDriver.cpp +++ b/FluidNC/src/Motors/TrinamicUartDriver.cpp @@ -21,10 +21,7 @@ namespace MotorDrivers { void TrinamicUartDriver::init() { _uart = config->_uarts[_uart_num]; - if (!_uart) { - log_error("TMC Driver missing uart" << _uart_num << " section"); - return; - } + Assert(_uart, "TMC Driver missing uart%d section", _uart_num); _cs_pin.setAttr(Pin::Attr::Output); } diff --git a/FluidNC/src/Pin.cpp b/FluidNC/src/Pin.cpp index 01c606f6c..5e22afacf 100644 --- a/FluidNC/src/Pin.cpp +++ b/FluidNC/src/Pin.cpp @@ -12,7 +12,6 @@ #include "Pins/I2SOPinDetail.h" #include "Pins/ErrorPinDetail.h" #include "string_util.h" -#include // snprintf() Pins::PinDetail* Pin::undefinedPin = new Pins::VoidPinDetail(); Pins::PinDetail* Pin::errorPin = new Pins::ErrorPinDetail("unknown"); @@ -113,9 +112,7 @@ Pin Pin::create(std::string_view str) { } } catch (const AssertionFailed& ex) { // We shouldn't get here under normal circumstances. log_error("ERR: " << str << " - " << ex.what()); - char buf[255]; - snprintf(buf, 255, "ERR: %s - %s", str, ex.what()); - Assert(false, buf); + Assert(false, ""); // return Pin(new Pins::ErrorPinDetail(str.str())); } } diff --git a/FluidNC/src/Pins/DebugPinDetail.cpp b/FluidNC/src/Pins/DebugPinDetail.cpp index 63e72d236..7bac835e6 100644 --- a/FluidNC/src/Pins/DebugPinDetail.cpp +++ b/FluidNC/src/Pins/DebugPinDetail.cpp @@ -5,28 +5,15 @@ #include "../UartChannel.h" #include // millis() -#include // vsnprintf -#include namespace Pins { - inline void WriteSerial(const char* format, ...) { - char buf[50]; - va_list arg; - va_list copy; - va_start(arg, format); - va_copy(copy, arg); - size_t len = vsnprintf(buf, 50, format, arg); - va_end(copy); - log_msg_to(Uart0, buf); - va_end(arg); - } // I/O: void DebugPinDetail::write(int high) { if (high != int(_isHigh)) { _isHigh = bool(high); if (shouldEvent()) { - WriteSerial("Write %s < %d", toString(), high); + log_msg_to(Uart0, "Write " << toString() << " < " << high); } } _implementation->write(high); @@ -35,7 +22,7 @@ namespace Pins { int DebugPinDetail::read() { auto result = _implementation->read(); if (shouldEvent()) { - WriteSerial("Read %s > %d", toString(), result); + log_msg_to(Uart0, "Read " << toString() << " > " << result); } return result; } @@ -63,10 +50,10 @@ namespace Pins { if (value.has(PinAttributes::InitialOn)) { buf[n++] = '+'; } - buf[n++] = 0; + buf[n++] = '\0'; if (shouldEvent()) { - WriteSerial("Set pin attr %s = %s", toString(), buf); + log_msg_to(Uart0, "Set pin attr " << toString() << " = " << buf); } _implementation->setAttr(value); } @@ -76,7 +63,7 @@ namespace Pins { void DebugPinDetail::CallbackHandler::handle(void* arg) { auto handler = static_cast(arg); if (handler->_myPin->shouldEvent()) { - WriteSerial("Received ISR on %s", handler->_myPin->toString()); + log_msg_to(Uart0, "Received ISR on " << handler->_myPin->toString()); } handler->callback(handler->argument); } @@ -88,7 +75,7 @@ namespace Pins { _isrHandler.callback = callback; if (shouldEvent()) { - WriteSerial("Attaching interrupt to pin %s, mode %d", toString(), mode); + log_msg_to(Uart0, "Attaching interrupt to pin " << toString() << ", mode " << mode); } _implementation->attachInterrupt(_isrHandler.handle, &_isrHandler, mode); } @@ -109,7 +96,7 @@ namespace Pins { } else if (_eventCount == 10) { _lastEvent = time; ++_eventCount; - WriteSerial("Suppressing events..."); + log_msg_to(Uart0, "Suppressing events..."); return false; } else { _lastEvent = time; diff --git a/FluidNC/src/Pins/GPIOPinDetail.cpp b/FluidNC/src/Pins/GPIOPinDetail.cpp index fa1c428d0..b10172c2e 100644 --- a/FluidNC/src/Pins/GPIOPinDetail.cpp +++ b/FluidNC/src/Pins/GPIOPinDetail.cpp @@ -29,6 +29,8 @@ namespace Pins { PinCapabilities::UART; case 5: + case 9: + case 10: case 16: case 17: case 18: @@ -62,8 +64,6 @@ namespace Pins { case 6: // SPI flash integrated case 7: case 8: - case 9: - case 10: case 11: return PinCapabilities::Reserved; diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index 467556244..4c2a29dab 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -705,7 +705,7 @@ static Error showChannelInfo(const char* value, WebUI::AuthenticationLevel auth_ } static Error showStartupLog(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { - startupLog.dump(out); + StartupLog::dump(out); return Error::Ok; } diff --git a/FluidNC/src/Report.h b/FluidNC/src/Report.h index 48d03da6e..221b9015f 100644 --- a/FluidNC/src/Report.h +++ b/FluidNC/src/Report.h @@ -92,6 +92,7 @@ const char* state_name(); extern const char* grbl_version; extern const char* git_info; +extern const char* git_url; // Callout to custom code void display_init(); diff --git a/FluidNC/src/StartupLog.cpp b/FluidNC/src/StartupLog.cpp deleted file mode 100644 index 0e36e71fb..000000000 --- a/FluidNC/src/StartupLog.cpp +++ /dev/null @@ -1,21 +0,0 @@ -#include "StartupLog.h" -#include -#include "Protocol.h" // send_line() - -size_t StartupLog::write(uint8_t data) { - _messages += (char)data; - return 1; -} -std::string StartupLog::messages() { - return _messages; -} -void StartupLog::dump(Channel& out) { - std::istringstream iss(_messages); - for (std::string line; std::getline(iss, line);) { - log_to(out, line); - } -} - -StartupLog::~StartupLog() {} - -StartupLog startupLog("Startup Log"); diff --git a/FluidNC/src/StartupLog.h b/FluidNC/src/StartupLog.h index 51176a2e8..fd678f127 100644 --- a/FluidNC/src/StartupLog.h +++ b/FluidNC/src/StartupLog.h @@ -6,19 +6,16 @@ #include "Config.h" #include "Channel.h" -#include class StartupLog : public Channel { -private: - std::string _messages; - public: - StartupLog(const char* name) : Channel(name) {} + StartupLog() : Channel("Startup Log") {} virtual ~StartupLog(); - size_t write(uint8_t data) override; - std::string messages(); - void dump(Channel& channel); + size_t write(uint8_t data) override; + + static void init(); + static void dump(Channel& channel); }; extern StartupLog startupLog; diff --git a/FluidNC/src/Status_outputs.cpp b/FluidNC/src/Status_outputs.cpp new file mode 100644 index 000000000..2ed99b8f5 --- /dev/null +++ b/FluidNC/src/Status_outputs.cpp @@ -0,0 +1,77 @@ +// Copyright (c) 2023 - Bart Dring +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +/* + This is a class for status "Idle,Run,Hold,Alarm" pins. + + This can be used for Tower lights,etc. +*/ +#include "Status_outputs.h" +#include "Machine/MachineConfig.h" + +void Status_Outputs::init() { + if (_Idle_pin.defined()) { + _Idle_pin.setAttr(Pin::Attr::Output); + } + + if (_Run_pin.defined()) { + _Run_pin.setAttr(Pin::Attr::Output); + } + + if (_Hold_pin.defined()) { + _Hold_pin.setAttr(Pin::Attr::Output); + } + + if (_Alarm_pin.defined()) { + _Alarm_pin.setAttr(Pin::Attr::Output); + } + + log_info("Status outputs" + << " Interval:" << _interval_ms << " Idle:" << _Idle_pin.name() << " Cycle:" << _Run_pin.name() << " Hold:" << _Hold_pin.name() + << " Alarm:" << _Alarm_pin.name()); + + allChannels.registration(this); + setReportInterval(_interval_ms); +} + +void Status_Outputs::parse_report() { + if (_report.rfind("<", 0) == 0) { + parse_status_report(); + return; + } +} + +// This is how the OLED driver receives channel data +size_t Status_Outputs::write(uint8_t data) { + char c = data; + if (c == '\r') { + return 1; + } + if (c == '\n') { + parse_report(); + _report = ""; + return 1; + } + _report += c; + return 1; +} + +Channel* Status_Outputs::pollLine(char* line) { + autoReport(); + return nullptr; +} + +void Status_Outputs::parse_status_report() { + if (_report.back() == '>') { + _report.pop_back(); + } + // Now the string is a sequence of field|field|field + size_t pos = 0; + auto nextpos = _report.find_first_of("|", pos); + _state = _report.substr(pos + 1, nextpos - pos - 1); + + _Idle_pin.write(_state == "Idle"); + _Run_pin.write(_state == "Run"); + _Hold_pin.write(_state.substr(0, 4) == "Hold"); + _Alarm_pin.write(_state == "Alarm"); +} diff --git a/FluidNC/src/Status_outputs.h b/FluidNC/src/Status_outputs.h new file mode 100644 index 000000000..793624288 --- /dev/null +++ b/FluidNC/src/Status_outputs.h @@ -0,0 +1,56 @@ +#pragma once + +#include "Config.h" +#include "Configuration/Configurable.h" +#include "Channel.h" + +typedef const uint8_t* font_t; + +class Status_Outputs : public Channel, public Configuration::Configurable { + Pin _Idle_pin; + Pin _Run_pin; + Pin _Hold_pin; + Pin _Alarm_pin; + +public: +private: + std::string _report; + std::string _state; + + int _interval_ms = 500; + + void parse_report(); + void parse_status_report(); + +public: + Status_Outputs() : Channel("status_outputs") {} + + Status_Outputs(const Status_Outputs&) = delete; + Status_Outputs(Status_Outputs&&) = delete; + Status_Outputs& operator=(const Status_Outputs&) = delete; + Status_Outputs& operator=(Status_Outputs&&) = delete; + + virtual ~Status_Outputs() = default; + + void init(); + + size_t write(uint8_t data) override; + + Channel* pollLine(char* line) override; + void flushRx() override {} + + bool lineComplete(char*, char) override { return false; } + size_t timedReadBytes(char* buffer, size_t length, TickType_t timeout) override { return 0; } + + // Configuration handlers: + void validate() override {} + void afterParse() override {}; + + void group(Configuration::HandlerBase& handler) override { + handler.item("report_interval_ms", _interval_ms, 100, 5000); + handler.item("idle_pin", _Idle_pin); + handler.item("run_pin", _Run_pin); + handler.item("hold_pin", _Hold_pin); + handler.item("alarm_pin", _Alarm_pin); + } +}; diff --git a/FluidNC/src/WebUI/TelnetServer.cpp b/FluidNC/src/WebUI/TelnetServer.cpp index 4f00c486c..f8329f9a2 100644 --- a/FluidNC/src/WebUI/TelnetServer.cpp +++ b/FluidNC/src/WebUI/TelnetServer.cpp @@ -9,14 +9,14 @@ #ifdef ENABLE_WIFI namespace WebUI { - TelnetServer telnetServer __attribute__((init_priority(107))); + TelnetServer telnetServer __attribute__((init_priority(107))) ; } # include "WifiServices.h" # include "WifiConfig.h" # include "../Report.h" // report_init_message() -# include "Commands.h" // COMMANDS +# include "Commands.h" // COMMANDS # include @@ -50,9 +50,7 @@ namespace WebUI { _setupdone = true; //add mDNS - if (WebUI::wifi_sta_ssdp->get() == SSDP_ENABLED) { - MDNS.addService("telnet", "tcp", _port); - } + MDNS.addService("telnet", "tcp", _port); return no_error; } diff --git a/FluidNC/src/WebUI/WebServer.cpp b/FluidNC/src/WebUI/WebServer.cpp index 8710c7cd0..2c0bf3e89 100644 --- a/FluidNC/src/WebUI/WebServer.cpp +++ b/FluidNC/src/WebUI/WebServer.cpp @@ -58,7 +58,7 @@ namespace WebUI { static const char LOCATION_HEADER[] = "Location"; - Web_Server webServer __attribute__((init_priority(108))); + Web_Server webServer __attribute__((init_priority(108))) ; bool Web_Server::_setupdone = false; uint16_t Web_Server::_port = 0; @@ -159,7 +159,7 @@ namespace WebUI { } //SSDP service presentation - if (WiFi.getMode() == WIFI_STA && WebUI::wifi_sta_ssdp->get() == SSDP_ENABLED) { + if (WiFi.getMode() == WIFI_STA) { _webserver->on("/description.xml", HTTP_GET, handle_SSDP); //Add specific for SSDP SSDP.setSchemaURL("description.xml"); @@ -185,7 +185,7 @@ namespace WebUI { _webserver->begin(); //add mDNS - if (WiFi.getMode() == WIFI_STA && WebUI::wifi_sta_ssdp->get() == SSDP_ENABLED) { + if (WiFi.getMode() == WIFI_STA) { MDNS.addService("http", "tcp", _port); } diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index 49c542e58..6798fc4f2 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -8,14 +8,14 @@ #include #include -WebUI::WiFiConfig wifi_config __attribute__((init_priority(109))); +WebUI::WiFiConfig wifi_config __attribute__((init_priority(109))) ; #ifdef ENABLE_WIFI # include "../Config.h" # include "../Main.h" -# include "Commands.h" // COMMANDS -# include "WifiServices.h" // wifi_services.start() etc. -# include "WebSettings.h" // split_params(), get_params() +# include "Commands.h" // COMMANDS +# include "WifiServices.h" // wifi_services.start() etc. +# include "WebSettings.h" // split_params(), get_params() # include "WebServer.h" // webServer.port() # include "TelnetServer.h" // telnetServer @@ -114,7 +114,6 @@ namespace WebUI { IPaddrSetting* wifi_sta_ip; IPaddrSetting* wifi_sta_gateway; IPaddrSetting* wifi_sta_netmask; - EnumSetting* wifi_sta_ssdp; StringSetting* wifi_ap_ssid; StringSetting* wifi_ap_password; @@ -140,14 +139,7 @@ namespace WebUI { { "WPA2-ENTERPRISE", WIFI_AUTH_WPA2_ENTERPRISE }, }; - enum_opt_t staSsdpModeOptions = { - { "Enable", SSDP_ENABLED }, - { "Disabled", SSDP_DISABLED }, - }; - - static void print_mac(Channel& out, const char* prefix, const char* mac) { - log_to(out, prefix, " (" << mac << ")"); - } + static void print_mac(Channel& out, const char* prefix, const char* mac) { log_to(out, prefix, " (" << mac << ")"); } static Error showIP(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP111 log_to(out, parameter, IP_string(WiFi.getMode() == WIFI_STA ? WiFi.localIP() : WiFi.softAPIP())); @@ -346,9 +338,7 @@ namespace WebUI { MAX_PASSWORD_LENGTH, (bool (*)(char*))WiFiConfig::isPasswordValid); wifi_ap_ssid = new StringSetting("AP SSID", WEBSET, WA, "ESP105", "AP/SSID", DEFAULT_AP_SSID, MIN_SSID_LENGTH, MAX_SSID_LENGTH, NULL); - wifi_ap_country = new EnumSetting("AP regulatory domain", WEBSET, WA, NULL, "AP/Country", WiFiCountry01, &wifiContryOptions, NULL); - wifi_sta_ssdp = - new EnumSetting("SSDP and mDNS enable", WEBSET, WA, NULL, "Sta/SSDP/Enable", DEFAULT_STA_SSDP_MODE, &onoffOptions, NULL); + wifi_ap_country = new EnumSetting("AP regulatory domain", WEBSET, WA, NULL, "AP/Country", WiFiCountry01, &wifiContryOptions, NULL); wifi_sta_netmask = new IPaddrSetting("Station Static Mask", WEBSET, WA, NULL, "Sta/Netmask", DEFAULT_STA_MK, NULL); wifi_sta_gateway = new IPaddrSetting("Station Static Gateway", WEBSET, WA, NULL, "Sta/Gateway", DEFAULT_STA_GW, NULL); wifi_sta_ip = new IPaddrSetting("Station Static IP", WEBSET, WA, NULL, "Sta/IP", DEFAULT_STA_IP, NULL); @@ -787,9 +777,7 @@ namespace WebUI { /** * End WiFi */ - void WiFiConfig::end() { - StopWiFi(); - } + void WiFiConfig::end() { StopWiFi(); } /** * Reset ESP @@ -809,16 +797,12 @@ namespace WebUI { } log_info("WiFi reset done"); } - bool WiFiConfig::isOn() { - return !(WiFi.getMode() == WIFI_MODE_NULL); - } + bool WiFiConfig::isOn() { return !(WiFi.getMode() == WIFI_MODE_NULL); } /** * Handle not critical actions that must be done in sync environment */ - void WiFiConfig::handle() { - wifi_services.handle(); - } + void WiFiConfig::handle() { wifi_services.handle(); } // Used by js/scanwifidlg.js Error WiFiConfig::listAPs(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP410 @@ -832,7 +816,7 @@ namespace WebUI { case -2: // Scan not triggered WiFi.scanNetworks(true); // Begin async scan break; - case -1: // Scan in progress + case -1: // Scan in progress break; default: for (int i = 0; i < n; ++i) { @@ -857,8 +841,6 @@ namespace WebUI { return Error::Ok; } - WiFiConfig::~WiFiConfig() { - end(); - } + WiFiConfig::~WiFiConfig() { end(); } } #endif diff --git a/FluidNC/src/WebUI/WifiConfig.h b/FluidNC/src/WebUI/WifiConfig.h index b13a1d0c1..ad818e294 100644 --- a/FluidNC/src/WebUI/WifiConfig.h +++ b/FluidNC/src/WebUI/WifiConfig.h @@ -41,9 +41,6 @@ namespace WebUI { static const int DHCP_MODE = 0; static const int STATIC_MODE = 1; - static const int SSDP_DISABLED = 0; - static const int SSDP_ENABLED = 1; - //defaults values static const char* DEFAULT_HOSTNAME = "fluidnc"; static const char* DEFAULT_STA_SSID = ""; @@ -59,7 +56,6 @@ namespace WebUI { static const int DEFAULT_STA_MIN_SECURITY = WIFI_AUTH_WPA2_PSK; static const int DEFAULT_STA_IP_MODE = DHCP_MODE; - static const int DEFAULT_STA_SSDP_MODE = SSDP_ENABLED; static const char* HIDDEN_PASSWORD = "********"; //boundaries @@ -128,7 +124,6 @@ namespace WebUI { extern IPaddrSetting* wifi_sta_ip; extern IPaddrSetting* wifi_sta_gateway; extern IPaddrSetting* wifi_sta_netmask; - extern EnumSetting* wifi_sta_ssdp; extern StringSetting* wifi_ap_ssid; extern StringSetting* wifi_ap_password; diff --git a/FluidNC/src/WebUI/WifiServices.cpp b/FluidNC/src/WebUI/WifiServices.cpp index b0ff51f0e..d01a002c6 100644 --- a/FluidNC/src/WebUI/WifiServices.cpp +++ b/FluidNC/src/WebUI/WifiServices.cpp @@ -82,7 +82,7 @@ namespace WebUI { }); ArduinoOTA.begin(); //no need in AP mode - if (WiFi.getMode() == WIFI_STA && WebUI::wifi_sta_ssdp->get() == SSDP_ENABLED) { + if (WiFi.getMode() == WIFI_STA) { //start mDns const char* h = wifi_hostname->get(); if (!MDNS.begin(h)) { diff --git a/git-version.py b/git-version.py index 4f1d9df8f..bc76b17d8 100644 --- a/git-version.py +++ b/git-version.py @@ -12,6 +12,7 @@ if gitFail: tag = "v3.0.x" rev = " (noGit)" + url = " (noGit)" else: try: tag = ( @@ -47,17 +48,24 @@ dirty = "-dirty" else: dirty = "" - rev = " (%s-%s%s)" % (branchname, revision, dirty) + url = ( + subprocess.check_output(["git", "config", "--get", "remote.origin.url"]) + .strip() + .decode("utf-8") + ) + grbl_version = tag.replace('v','').rpartition('.')[0] git_info = '%s%s' % (tag, rev) +git_url = url provisional = "FluidNC/src/version.cxx" final = "FluidNC/src/version.cpp" with open(provisional, "w") as fp: fp.write('const char* grbl_version = \"' + grbl_version + '\";\n') fp.write('const char* git_info = \"' + git_info + '\";\n') + fp.write('const char* git_url = \"' + git_url + '\";\n') if not os.path.exists(final): # No version.cpp so rename version.cxx to version.cpp