diff --git a/.github/workflows/manual.yml b/.github/workflows/manual.yml index a72395b65..4651b2d51 100644 --- a/.github/workflows/manual.yml +++ b/.github/workflows/manual.yml @@ -43,4 +43,4 @@ jobs: uses: actions/upload-artifact@v2 with: name: releaseZipFile - path: release \ No newline at end of file + path: release diff --git a/FluidNC/Custom/oled_basic.cpp b/FluidNC/Custom/oled_basic.cpp index 3f18c5c30..49d280d84 100644 --- a/FluidNC/Custom/oled_basic.cpp +++ b/FluidNC/Custom/oled_basic.cpp @@ -1,3 +1,4 @@ +#if 0 // Copyright (c) 2020 - Bart Dring // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. @@ -16,8 +17,9 @@ Library Infor: https://github.com/ThingPulse/esp8266-oled-ssd1306 + Install to PlatformIO with this typed at the terminal - platformio lib install 562 + platformio lib install 2978 Add this to your machine definition file #define DISPLAY_CODE_FILENAME "Custom/oled_basic.cpp" @@ -26,7 +28,7 @@ // Include the correct display library #include "SSD1306Wire.h" -#include "../src/WebUI/WebSettings.h" +#include "../WebUI/WebSettings.h" #ifndef OLED_ADDRESS # define OLED_ADDRESS 0x3c @@ -216,7 +218,7 @@ void displayUpdate(void* pvParameters) { sd_get_current_filename(path); display.drawString(63, 12, path); - int progress = sd_report_perc_complete(); + int progress = sd_percent_complete(); // draw the progress bar display.drawProgressBar(0, 45, 120, 10, progress); @@ -240,7 +242,7 @@ void displayUpdate(void* pvParameters) { void display_init() { // Initialising the UI will init the display too. - log_info("Init Basic OLED SDA:" << pinName(OLED_SDA) << " SCL:" pinName(OLED_SCL)); + log_info("Init Basic OLED SDA:gpio." << OLED_SDA << " SCL:gpio." OLED_SCL); display.init(); display.flipScreenVertically(); @@ -269,3 +271,4 @@ void display_init() { // core ); } +#endif \ No newline at end of file diff --git a/FluidNC/src/Config.h b/FluidNC/src/Config.h index 8bf95006e..b11382e60 100644 --- a/FluidNC/src/Config.h +++ b/FluidNC/src/Config.h @@ -216,3 +216,14 @@ const double PARKING_RATE = 800.0; // Parking fast rate after pull const double PARKING_PULLOUT_RATE = 250.0; // Pull-out/plunge slow feed rate in mm/min. const double PARKING_PULLOUT_INCREMENT = 5.0; // Spindle pull-out and plunge distance in mm. Incremental distance. // Must be positive value or equal to zero. + +// INCLUDE_OLED_IO enables access to a basic OLED library. To use it you must uncomment the +// "thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays" line in platformio.ini +// You must uncomment it if you use either INCLUDE_OLED_TINY or INCLUDE_OLED_BASIC +// #define INCLUDE_OLED_IO + +// INCLUDE_OLED_TINY includes a driver for a very small 64x48 OLED display +// #define INCLUDE_OLED_TINY + +// INCLUDE_OLED_BASIC includes a driver for a modest sized OLED display +// #define INCLUDE_OLED_BASIC diff --git a/FluidNC/src/Configuration/JsonGenerator.cpp b/FluidNC/src/Configuration/JsonGenerator.cpp index 8ddf3dc08..9c10c1431 100644 --- a/FluidNC/src/Configuration/JsonGenerator.cpp +++ b/FluidNC/src/Configuration/JsonGenerator.cpp @@ -51,7 +51,7 @@ namespace Configuration { void JsonGenerator::item(const char* name, bool& value) { enter(name); const char* val = value ? "Yes" : "No"; - _encoder.begin_webui(name, _currentPath, "B", val); + _encoder.begin_webui(_currentPath, _currentPath, "B", val); _encoder.begin_array("O"); { _encoder.begin_object(); @@ -68,7 +68,7 @@ namespace Configuration { enter(name); char buf[32]; itoa(value, buf, 10); - _encoder.begin_webui(name, _currentPath, "I", buf, minValue, maxValue); + _encoder.begin_webui(_currentPath, _currentPath, "I", buf, minValue, maxValue); _encoder.end_object(); leave(); } @@ -76,7 +76,7 @@ namespace Configuration { void JsonGenerator::item(const char* name, float& value, float minValue, float maxValue) { enter(name); // WebUI does not explicitly recognize the R type, but nevertheless handles it correctly. - _encoder.begin_webui(name, _currentPath, "R", String(value, 3).c_str()); + _encoder.begin_webui(_currentPath, _currentPath, "R", String(value, 3).c_str()); _encoder.end_object(); leave(); } @@ -88,7 +88,7 @@ namespace Configuration { void JsonGenerator::item(const char* name, String& value, int minLength, int maxLength) { enter(name); - _encoder.begin_webui(name, _currentPath, "S", value.c_str(), minLength, maxLength); + _encoder.begin_webui(_currentPath, _currentPath, "S", value.c_str(), minLength, maxLength); _encoder.end_object(); leave(); } @@ -99,7 +99,7 @@ namespace Configuration { /* enter(name); auto sv = value.name(); - _encoder.begin_webui(name, _currentPath, "S", sv.c_str(), 0, 255); + _encoder.begin_webui(_currentPath, _currentPath, "S", sv.c_str(), 0, 255); _encoder.end_object(); leave(); */ @@ -107,7 +107,7 @@ namespace Configuration { void JsonGenerator::item(const char* name, IPAddress& value) { enter(name); - _encoder.begin_webui(name, _currentPath, "A", value.toString().c_str()); + _encoder.begin_webui(_currentPath, _currentPath, "A", value.toString().c_str()); _encoder.end_object(); leave(); } @@ -122,7 +122,7 @@ namespace Configuration { } } - _encoder.begin_webui(name, _currentPath, "B", str); + _encoder.begin_webui(_currentPath, _currentPath, "B", str); _encoder.begin_array("O"); for (; e->name; ++e) { _encoder.begin_object(); diff --git a/FluidNC/src/Control.h b/FluidNC/src/Control.h index 7a63e81c3..9dc523ae1 100644 --- a/FluidNC/src/Control.h +++ b/FluidNC/src/Control.h @@ -7,9 +7,9 @@ #include "ControlPin.h" class Control : public Configuration::Configurable { -private: +// private: // TODO: Should we not just put this in an array so we can enumerate it easily? - +public: ControlPin _safetyDoor; ControlPin _reset; ControlPin _feedHold; diff --git a/FluidNC/src/Custom/oled_basic.cpp b/FluidNC/src/Custom/oled_basic.cpp new file mode 100644 index 000000000..d44f33a2d --- /dev/null +++ b/FluidNC/src/Custom/oled_basic.cpp @@ -0,0 +1,249 @@ +// Copyright (c) 2020 - Bart Dring +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +/* + OLED display code. + + It is designed to be used with a machine that has no easily accessible serial connection + It shows basic status and connection information. + + When in alarm mode it will show the current Wifi/BT paramaters and status + Most machines will start in alarm mode (needs homing) + If the machine is running a job from SD it will show the progress + In other modes it will show state and 3 axis DROs + Thats All! +*/ +#include "../Config.h" + +#ifdef INCLUDE_OLED_BASIC +# include "oled_io.h" +# include "../Main.h" // display_init() + +# include "../Machine/MachineConfig.h" +# include "WiFi.h" +# include "../WebUI/WebSettings.h" +# include "../SettingsDefinitions.h" +# include "../Report.h" +# include "../Machine/Axes.h" +# include "../Uart.h" + +static TaskHandle_t oledUpdateTaskHandle = 0; + +// This displays the status of the ESP32 Radios...BT, WiFi, etc +static void oledRadioInfo() { + String radio_addr = ""; + String radio_name = ""; + String radio_status = ""; + +# ifdef ENABLE_BLUETOOTH + if (bt_enable->get()) { + radio_name = String("BT: ") + WebUI::bt_name->get(); + ; + } +# endif +# ifdef ENABLE_WIFI + if (radio_name == "") { + if ((WiFi.getMode() == WIFI_MODE_STA) || (WiFi.getMode() == WIFI_MODE_APSTA)) { + radio_name = "STA: " + WiFi.SSID(); + radio_addr = WiFi.localIP().toString(); + } else if ((WiFi.getMode() == WIFI_MODE_AP) || (WiFi.getMode() == WIFI_MODE_APSTA)) { + radio_name = String("AP:") + WebUI::wifi_ap_ssid->get(); + radio_addr = WiFi.softAPIP().toString(); + } else { + radio_name = "Radio Mode: None"; + } + } +# endif + + if (radio_name == "") { + radio_name = "Radio Mode:Disabled"; + } + + oled->setTextAlignment(TEXT_ALIGN_LEFT); + oled->setFont(ArialMT_Plain_10); + + if (sys.state == State::Alarm) { // print below Alarm: + oled->drawString(0, 18, radio_name); + oled->drawString(0, 30, radio_addr); + + } else { // print next to status +# ifdef ENABLE_BLUETOOTH + oled->drawString(55, 2, config->_comms->_bluetoothConfig ? radio_name : radio_addr); +# endif + } +} + +static void draw_checkbox(int16_t x, int16_t y, int16_t width, int16_t height, bool checked) { + if (checked) + oled->fillRect(x, y, width, height); // If log.0 + else + oled->drawRect(x, y, width, height); // If log.1 +} + +static void oledDRO() { + uint8_t oled_y_pos; + //float wco[MAX_N_AXIS]; + + oled->setTextAlignment(TEXT_ALIGN_LEFT); + oled->setFont(ArialMT_Plain_10); + + char axisVal[20]; + + oled->drawString(80, 14, "L"); // Limit switch + + auto n_axis = config->_axes->_numberAxis; + auto ctrl_pins = config->_control; + bool prb_pin_state = config->_probe->get_state(); + + oled->setTextAlignment(TEXT_ALIGN_RIGHT); + + float* print_position = get_mpos(); + if (bits_are_true(status_mask->get(), RtStatus::Position)) { + oled->drawString(60, 14, "M Pos"); + } else { + oled->drawString(60, 14, "W Pos"); + mpos_to_wpos(print_position); + } + + for (uint8_t axis = X_AXIS; axis < n_axis; axis++) { + oled_y_pos = 24 + (axis * 10); + + String axis_letter = String(Machine::Axes::_names[axis]); + axis_letter += ":"; + oled->setTextAlignment(TEXT_ALIGN_LEFT); + oled->drawString(0, oled_y_pos, axis_letter); // String('X') + ":"); + + oled->setTextAlignment(TEXT_ALIGN_RIGHT); + snprintf(axisVal, 20 - 1, "%.3f", print_position[axis]); + oled->drawString(60, oled_y_pos, axisVal); + + //if (bitnum_is_true(limitAxes, axis)) { // only draw the box if a switch has been defined + // draw_checkbox(80, 27 + (axis * 10), 7, 7, limits_check(bitnum_to_mask(axis))); + //} + } + + oled_y_pos = 14; + + if (config->_probe->exists()) { + oled->drawString(110, oled_y_pos, "P"); + draw_checkbox(120, oled_y_pos + 3, 7, 7, prb_pin_state); + oled_y_pos += 10; + } + if (ctrl_pins->_feedHold._pin.defined()) { + oled->drawString(110, oled_y_pos, "H"); + draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_feedHold.get()); + oled_y_pos += 10; + } + if (ctrl_pins->_cycleStart._pin.defined()) { + oled->drawString(110, oled_y_pos, "S"); + draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_cycleStart.get()); + oled_y_pos += 10; + } + + if (ctrl_pins->_reset._pin.defined()) { + oled->drawString(110, oled_y_pos, "R"); + draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_reset.get()); + oled_y_pos += 10; + } + + if (ctrl_pins->_safetyDoor._pin.defined()) { + oled->drawString(110, oled_y_pos, "D"); + draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_safetyDoor.get()); + oled_y_pos += 10; + } +} + +static void oledUpdate(void* pvParameters) { + TickType_t xLastWakeTime; + const TickType_t xOledFrequency = 100; // in ticks (typically ms) + xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time. + + vTaskDelay(2500); + uint16_t sd_file_ticker = 0; + + oled->init(); + oled->flipScreenVertically(); + + while (true) { + oled->clear(); + + String state_string = ""; + + oled->setTextAlignment(TEXT_ALIGN_LEFT); + oled->setFont(ArialMT_Plain_16); + oled->drawString(0, 0, state_name()); + + if (config->_sdCard->get_state() == SDCard::State::BusyPrinting) { + oled->clear(); + oled->setTextAlignment(TEXT_ALIGN_CENTER); + oled->setFont(ArialMT_Plain_10); + state_string = "SD File"; + for (int i = 0; i < sd_file_ticker % 10; i++) { + state_string += "."; + } + sd_file_ticker++; + oled->drawString(63, 0, state_string); + + oled->drawString(63, 12, config->_sdCard->filename()); + + int progress = config->_sdCard->percent_complete(); + // draw the progress bar + oled->drawProgressBar(0, 45, 120, 10, progress); + + // draw the percentage as String + oled->setFont(ArialMT_Plain_10); + oled->setTextAlignment(TEXT_ALIGN_CENTER); + oled->drawString(64, 25, String(progress) + "%"); + + } else if (sys.state == State::Alarm) { + oledRadioInfo(); + } else { + oledDRO(); + oledRadioInfo(); + } + + oled->display(); + + vTaskDelayUntil(&xLastWakeTime, xOledFrequency); + } +} + +void display_init() { + init_oled(0x3c, GPIO_NUM_14, GPIO_NUM_13, GEOMETRY_128_64); + + oled->flipScreenVertically(); + oled->setTextAlignment(TEXT_ALIGN_LEFT); + + oled->clear(); + oled->display(); + + xTaskCreatePinnedToCore(oledUpdate, // task + "oledUpdateTask", // name for task + 4096, // size of task stack + NULL, // parameters + 1, // priority + &oledUpdateTaskHandle, + CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core + // core + ); +} +static void oled_show_string(String s) { + oled->clear(); + oled->drawString(0, 0, s); + oled->display(); +} + +void display(const char* tag, String s) { + if (!strcmp(tag, "IP")) { + oled_show_string(s); + return; + } + if (!strcmp(tag, "MACHINE")) { + // remove characters from the end until the string fits + while (oled->getStringWidth(s) > 64) { + s = s.substring(0, s.length() - 1); + } + oled_show_string(s); + } +} +#endif diff --git a/FluidNC/src/Custom/oled_io.cpp b/FluidNC/src/Custom/oled_io.cpp new file mode 100644 index 000000000..83ead7c49 --- /dev/null +++ b/FluidNC/src/Custom/oled_io.cpp @@ -0,0 +1,30 @@ +// Copyright (c) 2020 - Bart Dring +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +/* + OLED initialization + + Library Info: + https://github.com/ThingPulse/esp8266-oled-ssd1306 + + Install to PlatformIO with this typed at the terminal + platformio lib install 2978 + + Uncomment the "thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays" + line in platformio.ini +*/ + +#include "../Config.h" + +#ifdef INCLUDE_OLED_IO +# include "oled_io.h" +# include "../Uart.h" + +SSD1306Wire* oled; + +void init_oled(uint8_t address, pinnum_t sda_gpio, pinnum_t scl_gpio, OLEDDISPLAY_GEOMETRY geometry) { + Uart0 << "[MSG:INFO Init OLED SDA:gpio." << sda_gpio << " SCL:gpio." << scl_gpio << "]\n"; + oled = new SSD1306Wire(address, sda_gpio, scl_gpio, geometry, I2C_ONE, 400000); + oled->init(); +} +#endif diff --git a/FluidNC/src/Custom/oled_io.h b/FluidNC/src/Custom/oled_io.h new file mode 100644 index 000000000..5ce340a7c --- /dev/null +++ b/FluidNC/src/Custom/oled_io.h @@ -0,0 +1,9 @@ +#pragma once + +#include +extern SSD1306Wire* oled; + +// The SDA and SCL pins must be ordinary GPIOs; mappings to Pin objects do not +// work because the Arduino Wire library performs GPIO setup operations that cannot +// be overridden. +void init_oled(uint8_t address, pinnum_t sda_gpio, pinnum_t scl_gpio, OLEDDISPLAY_GEOMETRY geometry); diff --git a/FluidNC/src/Custom/oled_tiny.cpp b/FluidNC/src/Custom/oled_tiny.cpp new file mode 100644 index 000000000..38fb3974c --- /dev/null +++ b/FluidNC/src/Custom/oled_tiny.cpp @@ -0,0 +1,85 @@ +// Copyright (c) 2021 - Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +/* + Tiny OLED display code. + + This is for a minature 64x48 OLED display that is too small to + display a lot of information at once. Display items are shown + mostly individually, formatted to be a readable as practical + on the tiny display. +*/ + +#include "../Config.h" + +#ifdef INCLUDE_OLED_TINY + +# include "oled_io.h" +# include "../Main.h" // display_init() and display() + +void display_init() { + // The following I2C address and GPIO numbers are correct + // for a WeMOS D1 Mini 0.66 OLED Shield attached to an + // ESP32 Mini board. + // Address SDA SCL + init_oled(0x3c, GPIO_NUM_21, GPIO_NUM_22, GEOMETRY_64_48); + + oled->flipScreenVertically(); + + oled->clear(); + oled->setLogBuffer(3, 10); + + oled->setTextAlignment(TEXT_ALIGN_LEFT); + + // The initial circle is a good indication of a recent reboot + oled->fillCircle(32, 24, 10); + + oled->display(); +} +static void oled_log_line(String line) { + if (line.length()) { + oled->clear(); + oled->setFont(ArialMT_Plain_10); + oled->println(line); + oled->drawLogBuffer(0, 0); + oled->display(); + } +} +void oled_fill_rect(int x, int y, int w, int h) { + oled->clear(); + oled->fillRect(x, y, w, h); + oled->display(); +} +static void oled_show_string(String s) { + oled->clear(); + oled->setFont(ArialMT_Plain_16); + oled->drawString(0, 0, s); + oled->display(); +} +static void oled_show_ip(String ip) { + auto dotpos = ip.lastIndexOf('.'); // Last . + dotpos = ip.substring(0, dotpos).lastIndexOf('.'); // Second to last . + + oled->clear(); + oled->setFont(ArialMT_Plain_16); + oled->drawString(0, 0, ip.substring(0, dotpos)); + oled->drawString(0, 16, ip.substring(dotpos)); + oled->display(); +} + +// display() is the only entry point for runtime usage +void display(const char* tag, String s) { + if (!strcmp(tag, "IP")) { + oled_show_ip(s); + return; + } + if (!strcmp(tag, "GCODE")) { + oled_log_line(s); + return; + } + if (!strcmp(tag, "TEXT")) { + oled_show_string(s); + return; + } +} +#endif diff --git a/FluidNC/src/GCode.cpp b/FluidNC/src/GCode.cpp index 64c516873..e1cbd76d1 100644 --- a/FluidNC/src/GCode.cpp +++ b/FluidNC/src/GCode.cpp @@ -502,7 +502,7 @@ Error gc_execute_line(char* line, Print& client) { gc_block.modal.spindle = SpindleState::Cw; break; case 4: // Supported if the spindle can be reversed or laser mode is on. - if (spindle->is_reversable || config->_laserMode) { + if (spindle->is_reversable || spindle->isRateAdjusted()) { gc_block.modal.spindle = SpindleState::Ccw; } else { FAIL(Error::GcodeUnsupportedCommand); @@ -1323,10 +1323,11 @@ Error gc_execute_line(char* line, Print& client) { return status == Error::JogCancelled ? Error::Ok : status; } // If in laser mode, setup laser power based on current and past parser conditions. - if (config->_laserMode) { + if (spindle->isRateAdjusted()) { if (!((gc_block.modal.motion == Motion::Linear) || (gc_block.modal.motion == Motion::CwArc) || (gc_block.modal.motion == Motion::CcwArc))) { - gc_parser_flags |= GCParserLaserDisable; + if (gc_state.modal.spindle == SpindleState::Ccw) + gc_parser_flags |= GCParserLaserDisable; } // Any motion mode with axis words is allowed to be passed from a spindle speed update. // NOTE: G1 and G0 without axis words sets axis_command to none. G28/30 are intentionally omitted. diff --git a/FluidNC/src/GCode.h b/FluidNC/src/GCode.h index a4262bf2c..7c5ed8941 100644 --- a/FluidNC/src/GCode.h +++ b/FluidNC/src/GCode.h @@ -210,8 +210,8 @@ enum GCParserFlags { GCParserProbeIsAway = bitnum_to_mask(3), GCParserProbeIsNoError = bitnum_to_mask(4), GCParserLaserForceSync = bitnum_to_mask(5), - GCParserLaserDisable = bitnum_to_mask(6), - GCParserLaserIsMotion = bitnum_to_mask(7), + GCParserLaserDisable = bitnum_to_mask(6), // disable laser when motion stops + GCParserLaserIsMotion = bitnum_to_mask(7), // }; // Various places in the code access saved coordinate system data diff --git a/FluidNC/src/Limits.cpp b/FluidNC/src/Limits.cpp index 4a86f6262..b4845d21f 100644 --- a/FluidNC/src/Limits.cpp +++ b/FluidNC/src/Limits.cpp @@ -41,6 +41,10 @@ MotorMask limits_get_state() { return Machine::Axes::posLimitMask | Machine::Axes::negLimitMask; } +bool ambiguousLimit() { + return Machine::Axes::posLimitMask & Machine::Axes::negLimitMask; +} + bool soft_limit = false; // Performs a soft limit check. Called from mcline() only. Assumes the machine has been homed, diff --git a/FluidNC/src/Limits.h b/FluidNC/src/Limits.h index 2db689e36..daa032ec4 100644 --- a/FluidNC/src/Limits.h +++ b/FluidNC/src/Limits.h @@ -32,3 +32,9 @@ void limitCheckTask(void* pvParameters); bool limitsCheckTravel(float* target); bool user_defined_homing(AxisMask cycle_mask); + +// True if an axis is reporting engaged limits on both ends. This +// typically happens when the same pin is used for a pair of switches, +// so you cannot tell which one is triggered. In that case, automatic +// pull-off is impossible. +bool ambiguousLimit(); diff --git a/FluidNC/src/Machine/Axes.h b/FluidNC/src/Machine/Axes.h index 05fe42682..164a8aaff 100644 --- a/FluidNC/src/Machine/Axes.h +++ b/FluidNC/src/Machine/Axes.h @@ -13,7 +13,6 @@ namespace MotorDrivers { namespace Machine { class Axes : public Configuration::Configurable { - static constexpr const char* _names = "XYZABC"; bool _switchedStepper = false; @@ -22,6 +21,8 @@ namespace Machine { MotorMask _motorLockoutMask = 0; public: + static constexpr const char* _names = "XYZABC"; + Axes(); // Bitmasks to collect information about axes that have limits and homing diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index ef610a5ee..c3dd5aaf3 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -45,7 +45,6 @@ namespace Machine { handler.section("user_outputs", _userOutputs); handler.item("software_debounce_ms", _softwareDebounceMs); // TODO: Consider putting these under a gcode: hierarchy level? Or motion control? - handler.item("laser_mode", _laserMode); handler.item("arc_tolerance", _arcTolerance); handler.item("junction_deviation", _junctionDeviation); handler.item("verbose_errors", _verboseErrors); @@ -54,7 +53,6 @@ namespace Machine { handler.item("enable_parking_override_control", _enableParkingOverrideControl); handler.item("deactivate_parking_upon_init", _deactivateParkingUponInit); handler.item("check_limits_at_init", _checkLimitsAtInit); - handler.item("limits_two_switches_on_axis", _limitsTwoSwitchesOnAxis); handler.item("disable_laser_during_hold", _disableLaserDuringHold); handler.item("use_line_numbers", _useLineNumbers); diff --git a/FluidNC/src/Machine/MachineConfig.h b/FluidNC/src/Machine/MachineConfig.h index 00da02af7..90b98cea7 100644 --- a/FluidNC/src/Machine/MachineConfig.h +++ b/FluidNC/src/Machine/MachineConfig.h @@ -42,7 +42,6 @@ namespace Machine { Spindles::SpindleList _spindles; - bool _laserMode = false; float _arcTolerance = 0.002f; float _junctionDeviation = 0.01f; bool _verboseErrors = false; @@ -62,14 +61,6 @@ namespace Machine { // will be entered instead of Idle, messaging the user to check the limits, rather than idle. bool _checkLimitsAtInit = true; - // If your machine has two limits switches wired in parallel to one axis, you will need to enable - // this feature. Since the two switches are sharing a single pin, there is no way to tell - // which one is enabled. This option only effects homing, where if a limit is engaged, the system - // will alarm and force the user to manually disengage the limit switch. Otherwise, if you have one - // limit switch for each axis, don't enable this option. By keeping it disabled, you can perform a - // homing cycle while on the limit switch and not have to move the machine off of it. - bool _limitsTwoSwitchesOnAxis = false; - // This option will automatically disable the laser during a feed hold by invoking a spindle stop // override immediately after coming to a stop. However, this also means that the laser still may // be reenabled by disabling the spindle stop override, if needed. This is purely a safety feature diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 80b27a7a8..d27b7ce26 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -199,6 +199,8 @@ void WEAK_LINK machine_init() {} void WEAK_LINK display_init() {} +void WEAK_LINK display(const char* tag, String s) {} + #if 0 int main() { setup(); // setup() diff --git a/FluidNC/src/Main.h b/FluidNC/src/Main.h index c41a84ab0..82c5ea0c8 100644 --- a/FluidNC/src/Main.h +++ b/FluidNC/src/Main.h @@ -3,9 +3,12 @@ #pragma once +#include + void main_init(); void run_once(); // Callouts to custom code void machine_init(); void display_init(); +void display(const char* tag, String s); diff --git a/FluidNC/src/MotionControl.cpp b/FluidNC/src/MotionControl.cpp index fcf610953..58bac5a72 100644 --- a/FluidNC/src/MotionControl.cpp +++ b/FluidNC/src/MotionControl.cpp @@ -264,10 +264,10 @@ void mc_homing_cycle(AxisMask axis_mask) { if (kinematics_pre_homing(axis_mask)) { return; } - // Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems - // with machines with limits wired on both ends of travel to one limit pin. - // TODO: Move the pin-specific LIMIT_PIN call to Limits.cpp as a function. - if (config->_limitsTwoSwitchesOnAxis && limits_get_state()) { + // Abort homing cycle if an axis has limit switches engaged on both ends, + // or if it is impossible to tell which end is engaged. In that situation + // we do not know the pulloff direction. + if (ambiguousLimit()) { mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. rtAlarm = ExecAlarm::HardLimit; return; diff --git a/FluidNC/src/PinMapper.cpp b/FluidNC/src/PinMapper.cpp index 092caa836..f2853320f 100644 --- a/FluidNC/src/PinMapper.cpp +++ b/FluidNC/src/PinMapper.cpp @@ -1,38 +1,60 @@ #include "PinMapper.h" +#include "Pins/GPIOPinDetail.h" #include "Assert.h" #include // PULLUP, INPUT, OUTPUT +extern "C" void __pinMode(pinnum_t pin, uint8_t mode); +extern "C" int __digitalRead(pinnum_t pin); +extern "C" void __digitalWrite(pinnum_t pin, uint8_t val); + +// Pin mapping lets you use non-GPIO pins as though they were GPIOs by +// storing Pin object references in an array indexed by a small +// integer. An offset is added to the index to push the number beyond +// the range of real GPIO numbers, while staying within the numeric +// range of a pinnum_t. That index+offset can be treated as a +// pinnum_t and passed to library routines whose API requires a GPIO +// number. This lets you use I2S pins for chip selects and possibly +// for other purposes. It works for libraries that use only +// pinMode(), digitalWrite() and digitalRead(), but fails for +// libraries that demand real GPIO pins, perhaps by modifying the IO +// Matrix. For such cases, the real GPIO number - lower than the +// offset - can be used directly. When the pinMode(), digitalWrite() +// and digitalRead() overloads encounter a real GPIO number, they pass +// the operation through to the lower level __pinMode(), +// __digitalRead() and __digitalWrite() routines. -// Pin mapping. Pretty straight forward, it's just a thing that stores pins in an array. -// -// The default behavior of a mapped pin is _undefined pin_, so it does nothing. namespace { - class Mapping { + class PinMap { public: - Pin* _mapping[256]; + static const int BOUNDARY = Pins::GPIOPinDetail::nGPIOPins; - Mapping() { - for (int i = 0; i < 256; ++i) { + private: + static const int N_PIN_MAPPINGS = 256 - BOUNDARY; + + public: + Pin* _mapping[N_PIN_MAPPINGS]; + + PinMap() { + for (int i = 0; i < N_PIN_MAPPINGS; ++i) { _mapping[i] = nullptr; } } pinnum_t Claim(Pin* pin) { - // Let's not use 0. 1 is the first pin we'll allocate. - for (pinnum_t i = 1; i < 256; ++i) { + for (pinnum_t i = 0; i < N_PIN_MAPPINGS; ++i) { if (_mapping[i] == nullptr) { _mapping[i] = pin; - return i; + return i + BOUNDARY; } } return 0; } - void Release(pinnum_t idx) { _mapping[idx] = nullptr; } + void Release(pinnum_t idx) { _mapping[idx - BOUNDARY] = nullptr; } - static Mapping& instance() { - static Mapping instance; + static PinMap& instance() { + static PinMap instance; return instance; } }; @@ -43,7 +65,7 @@ namespace { PinMapper::PinMapper() : _mappedId(0) {} PinMapper::PinMapper(Pin& pin) { - _mappedId = Mapping::instance().Claim(&pin); + _mappedId = PinMap::instance().Claim(&pin); // If you reach this assertion, you haven't been using the Pin class like you're supposed to. Assert(_mappedId != 0, "Cannot claim pin. We've reached the limit of 255 mapped pins."); @@ -58,7 +80,7 @@ PinMapper& PinMapper::operator=(PinMapper&& o) { // Special case for `a=a`. If we release there, things go wrong. if (&o != this) { if (_mappedId != 0) { - Mapping::instance().Release(_mappedId); + PinMap::instance().Release(_mappedId); _mappedId = 0; } std::swap(_mappedId, o._mappedId); @@ -69,19 +91,32 @@ PinMapper& PinMapper::operator=(PinMapper&& o) { // Clean up when we get destructed. PinMapper::~PinMapper() { if (_mappedId != 0) { - Mapping::instance().Release(_mappedId); + PinMap::instance().Release(_mappedId); } } // Arduino compatibility functions, which basically forward the call to the mapper: void IRAM_ATTR digitalWrite(pinnum_t pin, uint8_t val) { - auto thePin = Mapping::instance()._mapping[pin]; + if (pin < PinMap::BOUNDARY) { + return __digitalWrite(pin, val); + } + auto thePin = PinMap::instance()._mapping[pin - PinMap::BOUNDARY]; if (thePin) { thePin->synchronousWrite(val); } } void IRAM_ATTR pinMode(pinnum_t pin, uint8_t mode) { + if (pin < PinMap::PinMap::BOUNDARY) { + __pinMode(pin, mode); + return; + } + + auto thePin = PinMap::instance()._mapping[pin - PinMap::BOUNDARY]; + if (!thePin) { + return; + } + Pins::PinAttributes attr = Pins::PinAttributes::None; if ((mode & OUTPUT) == OUTPUT) { attr = attr | Pins::PinAttributes::Output; @@ -96,13 +131,13 @@ void IRAM_ATTR pinMode(pinnum_t pin, uint8_t mode) { attr = attr | Pins::PinAttributes::PullDown; } - auto thePin = Mapping::instance()._mapping[pin]; - if (thePin) { - thePin->setAttr(attr); - } + thePin->setAttr(attr); } int IRAM_ATTR digitalRead(pinnum_t pin) { - auto thePin = Mapping::instance()._mapping[pin]; + if (pin < PinMap::BOUNDARY) { + return __digitalRead(pin); + } + auto thePin = PinMap::instance()._mapping[pin - PinMap::BOUNDARY]; return (thePin) ? thePin->read() : 0; } diff --git a/FluidNC/src/PinMapper.h b/FluidNC/src/PinMapper.h index bc0494820..39fd9a9e8 100644 --- a/FluidNC/src/PinMapper.h +++ b/FluidNC/src/PinMapper.h @@ -3,8 +3,8 @@ // Pin mapper is a class that maps 'Pin' objects to Arduino digitalWrite / digitalRead / setMode. This // can be useful for support of external libraries, while keeping all the things that Pin has to offer. // -// It's designed to be easy to use. Basically just: `PinMapper myMap(pinToMap);`. It doesn't *own* the -// pin, it merely uses a pointer. Then, the external library can use `myMap.pinId()` as its pin number. +// It's designed to be easy to use. Basically just: `PinMapper myMap(pinToMap);`. It doesn't *own* the +// pin, it merely uses a pointer. Then, the external library can use `myMap.pinId()` as its pin number. // Once the mapper goes out of scope (or is destructed if it's a field), the mapping is implicitly removed. // Note that this is merely for external libraries that don't allow us to pass user data such as a void*... @@ -20,11 +20,11 @@ class PinMapper { // Constructor that maps a pin to some Arduino pin ID PinMapper(Pin& pin); - // Let's not create copies, that will go wrong... + // We do not want object copies PinMapper(const Pin& o) = delete; PinMapper& operator=(const Pin& o) = delete; - // For return values, we have to add some move semantics. This is just to + // For return values, we have to add some move semantics. This is just to // support trivial assignment cases and return values. Normally: don't use it. // All these constructors just pass along the id by swapping it. If a pinmapper // goes out of scope, it is destructed. diff --git a/FluidNC/src/Pins/GPIOPinDetail.h b/FluidNC/src/Pins/GPIOPinDetail.h index fa3952d85..59aae04b2 100644 --- a/FluidNC/src/Pins/GPIOPinDetail.h +++ b/FluidNC/src/Pins/GPIOPinDetail.h @@ -13,10 +13,11 @@ namespace Pins { static PinCapabilities GetDefaultCapabilities(pinnum_t index); - static const int nGPIOPins = 40; static std::vector _claimed; public: + static const int nGPIOPins = 40; + GPIOPinDetail(pinnum_t index, PinOptionsParser options); PinCapabilities capabilities() const override; diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index 5bbeadc5b..54e0946cb 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -488,6 +488,13 @@ static Error dump_config(const char* value, WebUI::AuthenticationLevel auth_leve return Error::Ok; } +static Error fakeLaserMode(const char* value, WebUI::AuthenticationLevel auth_level, Print& out) { + if (!value) { + out << "$32=" << (spindle->isRateAdjusted() ? "1" : "0") << '\n'; + } + return Error::Ok; +} + // Commands use the same syntax as Settings, but instead of setting or // displaying a persistent value, a command causes some action to occur. // That action could be anything, from displaying a run-time parameter @@ -527,6 +534,8 @@ void make_user_commands() { new UserCommand("I", "Build/Info", get_report_build_info, idleOrAlarm); new UserCommand("N", "GCode/StartupLines", report_startup_lines, idleOrAlarm); new UserCommand("RST", "Settings/Restore", restore_settings, idleOrAlarm, WA); + + new UserCommand("32", "FakeLaserMode", fakeLaserMode, idleOrAlarm); }; // normalize_key puts a key string into canonical form - @@ -554,7 +563,7 @@ char* normalize_key(char* start) { char* end; for (end = start; (c = *end) != '\0' && !isspace(c); end++) {} - // end now points to either a whitespace character of end of string + // end now points to either a whitespace character or end of string // In either case it is okay to place a null there *end = '\0'; diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 2d4c330c4..fa61e4a5f 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -78,10 +78,13 @@ union SpindleStop { static SpindleStop spindle_stop_ovr; bool can_park() { + if (spindle->isRateAdjusted()) { + return false; + } if (config->_enableParkingOverrideControl) { - return sys.override_ctrl == Override::ParkingMotion && Machine::Axes::homingMask && !config->_laserMode; + return sys.override_ctrl == Override::ParkingMotion && Machine::Axes::homingMask; } else { - return Machine::Axes::homingMask && !config->_laserMode; + return Machine::Axes::homingMask; } } @@ -766,7 +769,7 @@ static void protocol_exec_rt_suspend() { restore_spindle = block->spindle; restore_spindle_speed = block->spindle_speed; } - if (config->_disableLaserDuringHold && config->_laserMode) { + if (spindle->isRateAdjusted()) { rtAccessoryOverride.bit.spindleOvrStop = true; } @@ -871,7 +874,7 @@ static void protocol_exec_rt_suspend() { if (gc_state.modal.spindle != SpindleState::Disable) { // Block if safety door re-opened during prior restore actions. if (!sys.suspend.bit.restartRetract) { - if (config->_laserMode) { + if (spindle->isRateAdjusted()) { // When in laser mode, defer turn on until cycle starts sys.step_control.updateSpindleSpeed = true; } else { @@ -926,7 +929,7 @@ static void protocol_exec_rt_suspend() { } else if (spindle_stop_ovr.bit.restore || spindle_stop_ovr.bit.restoreCycle) { if (gc_state.modal.spindle != SpindleState::Disable) { report_feedback_message(Message::SpindleRestore); - if (config->_laserMode) { + if (spindle->isRateAdjusted()) { // When in laser mode, defer turn on until cycle starts sys.step_control.updateSpindleSpeed = true; } else { diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index 8cda30719..7dcfa5286 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -412,9 +412,6 @@ void report_build_info(const char* line, Print& client) { client << "M"; // TODO Need to deal with M8...it could be disabled } client << "PH"; - if (config->_limitsTwoSwitchesOnAxis) { - client << "L"; - } if (ALLOW_FEED_OVERRIDE_DURING_PROBE_CYCLES) { client << "A"; } @@ -483,7 +480,7 @@ static float* get_wco() { return wco; } -static void mpos_to_wpos(float* position) { +void mpos_to_wpos(float* position) { float* wco = get_wco(); auto n_axis = config->_axes->_numberAxis; for (int idx = 0; idx < n_axis; idx++) { @@ -491,7 +488,7 @@ static void mpos_to_wpos(float* position) { } } -static const char* state_name() { +const char* state_name() { switch (sys.state) { case State::Idle: return "Idle"; @@ -661,7 +658,7 @@ void report_realtime_status(Print& client) { } if (config->_sdCard->get_state() == SDCard::State::BusyPrinting) { // XXX WMB FORMAT 4.2f - client << "|SD:" << config->_sdCard->report_perc_complete() << "," << config->_sdCard->filename(); + client << "|SD:" << config->_sdCard->percent_complete() << "," << config->_sdCard->filename(); } #ifdef DEBUG_STEPPER_ISR client << "|ISRs:" << Stepper::isr_count; @@ -672,6 +669,18 @@ void report_realtime_status(Print& client) { client << ">\n"; } +void hex_msg(uint8_t* buf, const char* prefix, int len) { + char report[200]; + char temp[20]; + sprintf(report, "%s", prefix); + for (int i = 0; i < len; i++) { + sprintf(temp, " 0x%02X", buf[i]); + strcat(report, temp); + } + + log_info(report); +} + void reportTaskStackSize(UBaseType_t& saved) { #ifdef DEBUG_REPORT_STACK_FREE UBaseType_t newHighWater = uxTaskGetStackHighWaterMark(NULL); diff --git a/FluidNC/src/Report.h b/FluidNC/src/Report.h index 7705bfe71..5e60fb0c5 100644 --- a/FluidNC/src/Report.h +++ b/FluidNC/src/Report.h @@ -97,6 +97,8 @@ void report_realtime_debug(); void reportTaskStackSize(UBaseType_t& saved); +void hex_msg(uint8_t* buf, const char* prefix, int len); + void addPinReport(char* status, char pinLetter); extern const char* dataBeginMarker; @@ -104,5 +106,8 @@ extern const char* dataEndMarker; #include "MyIOStream.h" +void mpos_to_wpos(float* position); +const char* state_name(); + extern const char* grbl_version; extern const char* git_info; diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index 1cd60cb3c..c3415e9e3 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -103,7 +103,7 @@ Error SDCard::readFileLine(char* line, int maxlen) { } // return a percentage complete 50.5 = 50.5% -float SDCard::report_perc_complete() { +float SDCard::percent_complete() { if (!_pImpl->_file) { return 0.0; } diff --git a/FluidNC/src/SDCard.h b/FluidNC/src/SDCard.h index b7085de5c..2e4db76fe 100644 --- a/FluidNC/src/SDCard.h +++ b/FluidNC/src/SDCard.h @@ -77,7 +77,7 @@ class SDCard : public Configuration::Configurable { bool openFile(fs::FS& fs, const char* path, Print& client, WebUI::AuthenticationLevel auth_level); bool closeFile(); Error readFileLine(char* line, int len); - float report_perc_complete(); + float percent_complete(); uint32_t lineNumber(); void afterParse() override; diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index b7ec15eb0..e79ae40e3 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -49,6 +49,7 @@ #include "Protocol.h" // rtSafetyDoor etc #include "SDCard.h" #include "WebUI/InputBuffer.h" // XXX could this be a StringStream ? +#include "Main.h" // display() #include #include @@ -238,11 +239,15 @@ InputClient* pollClients() { client->_linelen = 0; continue; } - if (ch == '\r' || ch == '\n') { + if (ch == '\r') { + continue; + } + if (ch == '\n') { client->_line_num++; if (config->_sdCard->get_state() < SDCard::State::Busy) { client->_line[client->_linelen] = '\0'; client->_line_returned = true; + display("GCODE", client->_line); return client; } else { // Log an error and discard the line if it happens during an SD run diff --git a/FluidNC/src/Settings.cpp b/FluidNC/src/Settings.cpp index 746a86b97..93ab4aabb 100644 --- a/FluidNC/src/Settings.cpp +++ b/FluidNC/src/Settings.cpp @@ -183,7 +183,7 @@ const char* IntSetting::getStringValue() { void IntSetting::addWebui(WebUI::JSONencoder* j) { if (getDescription()) { - j->begin_webui(getName(), getDescription(), "I", getStringValue(), _minValue, _maxValue); + j->begin_webui(getName(), getName(), "I", getStringValue(), _minValue, _maxValue); j->end_object(); } } @@ -278,7 +278,7 @@ void StringSetting::addWebui(WebUI::JSONencoder* j) { if (!getDescription()) { return; } - j->begin_webui(getName(), getDescription(), "S", getStringValue(), _minLength, _maxLength); + j->begin_webui(getName(), getName(), "S", getStringValue(), _minLength, _maxLength); j->end_object(); } @@ -390,7 +390,7 @@ void EnumSetting::addWebui(WebUI::JSONencoder* j) { if (!getDescription()) { return; } - j->begin_webui(getName(), getDescription(), "B", String(get()).c_str()); + j->begin_webui(getName(), getName(), "B", String(get()).c_str()); j->begin_array("O"); for (enum_opt_t::iterator it = _options->begin(); it != _options->end(); it++) { j->begin_object(); @@ -520,7 +520,7 @@ const char* IPaddrSetting::getStringValue() { void IPaddrSetting::addWebui(WebUI::JSONencoder* j) { if (getDescription()) { - j->begin_webui(getName(), getDescription(), "A", getStringValue()); + j->begin_webui(getName(), getName(), "A", getStringValue()); j->end_object(); } } diff --git a/FluidNC/src/Spindles/H2ASpindle.h b/FluidNC/src/Spindles/H2ASpindle.h index 5854504fc..f10e122fc 100644 --- a/FluidNC/src/Spindles/H2ASpindle.h +++ b/FluidNC/src/Spindles/H2ASpindle.h @@ -16,7 +16,7 @@ namespace Spindles { response_parser get_current_direction(ModbusCommand& data) override; response_parser get_status_ok(ModbusCommand& data) override { return nullptr; } - bool supports_actual_speed() const override { return true; } + bool use_delay_settings() const override { return false; } bool safety_polling() const override { return false; } // Name of the configurable. Must match the name registered in the cpp file. diff --git a/FluidNC/src/Spindles/HuanyangSpindle.cpp b/FluidNC/src/Spindles/HuanyangSpindle.cpp index 92f21d908..0bcdc568d 100644 --- a/FluidNC/src/Spindles/HuanyangSpindle.cpp +++ b/FluidNC/src/Spindles/HuanyangSpindle.cpp @@ -203,6 +203,7 @@ namespace Spindles { data.msg[4] = dev_speed & 0xFF; } + // This gets data from the VFS. It does not set any values VFD::response_parser Huanyang::initialization_sequence(int index, ModbusCommand& data) { // NOTE: data length is excluding the CRC16 checksum. data.tx_length = 6; @@ -222,8 +223,9 @@ namespace Spindles { return [](const uint8_t* response, Spindles::VFD* vfd) -> bool { uint16_t value = (response[4] << 8) | response[5]; #ifdef DEBUG_VFD - log_debug("VFD: Max frequency = " << value); + log_debug("VFD: Max frequency = " << value / 100 << "Hz " << value / 100 * 60 << "RPM"); #endif + log_info("VFD: Max speed:" << (value / 100 * 60) << "rpm"); // Set current RPM value? Somewhere? auto huanyang = static_cast(vfd); @@ -239,8 +241,9 @@ namespace Spindles { uint16_t value = (response[4] << 8) | response[5]; #ifdef DEBUG_VFD - debug_all("VFD: Min frequency set to " << value); + log_debug("VFD: Min frequency = " << value / 100 << "Hz " << value / 100 * 60 << "RPM"); #endif + log_info("VFD: Min speed:" << (value / 100 * 60) << "rpm"); // Set current RPM value? Somewhere? auto huanyang = static_cast(vfd); diff --git a/FluidNC/src/Spindles/HuanyangSpindle.h b/FluidNC/src/Spindles/HuanyangSpindle.h index 830df46b3..fa675ae91 100644 --- a/FluidNC/src/Spindles/HuanyangSpindle.h +++ b/FluidNC/src/Spindles/HuanyangSpindle.h @@ -26,7 +26,7 @@ namespace Spindles { response_parser get_status_ok(ModbusCommand& data) override; response_parser get_current_speed(ModbusCommand& data) override; - bool supports_actual_speed() const override { return true; } + bool use_delay_settings() const override { return false; } // Name of the configurable. Must match the name registered in the cpp file. const char* name() const override { return "Huanyang"; } diff --git a/FluidNC/src/Spindles/Laser.cpp b/FluidNC/src/Spindles/Laser.cpp index 5bcea4236..bdc6e83d8 100644 --- a/FluidNC/src/Spindles/Laser.cpp +++ b/FluidNC/src/Spindles/Laser.cpp @@ -19,7 +19,7 @@ namespace Spindles { void Laser::config_message() { log_info(name() << " Spindle Ena:" << _enable_pin.name() << " Out:" << _output_pin.name() << " Freq:" << _pwm_freq - << "Hz Res:" << _pwm_precision << "bits Laser mode:" << (config->_laserMode ? "On" : "Off")); + << "Hz Res:" << _pwm_precision << "bits Laser mode:On"); } // Get the GPIO from the machine definition diff --git a/FluidNC/src/Spindles/Laser.h b/FluidNC/src/Spindles/Laser.h index 6734d9e34..65d9c8ea3 100644 --- a/FluidNC/src/Spindles/Laser.h +++ b/FluidNC/src/Spindles/Laser.h @@ -27,10 +27,18 @@ namespace Spindles { void config_message() override; void get_pins_and_settings() override; void set_direction(bool Clockwise) override {}; + bool use_delay_settings() const override { return false; } // Name of the configurable. Must match the name registered in the cpp file. const char* name() const override { return "Laser"; } - void group(Configuration::HandlerBase& handler) override { PWM::group(handler); } + void group(Configuration::HandlerBase& handler) override { + // pwm_freq is the only item that the PWM class adds to OnOff + // We cannot call PWM::group() because that would pick up + // direction_pin, which we do not want in Laser + handler.item("pwm_freq", _pwm_freq); + + OnOff::groupCommon(handler); + } ~Laser() {} }; diff --git a/FluidNC/src/Spindles/OnOffSpindle.h b/FluidNC/src/Spindles/OnOffSpindle.h index fe52ba383..8e3a86f33 100644 --- a/FluidNC/src/Spindles/OnOffSpindle.h +++ b/FluidNC/src/Spindles/OnOffSpindle.h @@ -13,6 +13,20 @@ namespace Spindles { // This is for an on/off spindle all RPMs above 0 are on class OnOff : public Spindle { + protected: + // This includes all items except direction_pin. direction_pin applies + // to most but not all of OnOff's derived classes. Derived classes that + // do not support direction_pin can invoke OnOff::groupCommon() instead + // of OnOff::group() + void groupCommon(Configuration::HandlerBase& handler) { + handler.item("output_pin", _output_pin); + handler.item("enable_pin", _enable_pin); + handler.item("disable_with_zero_speed", _disable_with_zero_speed); + handler.item("zero_speed_with_disable", _zero_speed_with_disable); + + Spindle::group(handler); + } + public: OnOff() = default; @@ -35,13 +49,8 @@ namespace Spindles { void validate() const override { Spindle::validate(); } void group(Configuration::HandlerBase& handler) override { - handler.item("output_pin", _output_pin); - handler.item("enable_pin", _enable_pin); handler.item("direction_pin", _direction_pin); - handler.item("disable_with_zero_speed", _disable_with_zero_speed); - handler.item("zero_speed_with_disable", _zero_speed_with_disable); - - Spindle::group(handler); + groupCommon(handler); } virtual ~OnOff() {} diff --git a/FluidNC/src/Spindles/PWMSpindle.cpp b/FluidNC/src/Spindles/PWMSpindle.cpp index 68e47aba2..f62986d90 100644 --- a/FluidNC/src/Spindles/PWMSpindle.cpp +++ b/FluidNC/src/Spindles/PWMSpindle.cpp @@ -89,9 +89,19 @@ namespace Spindles { // spinning down. set_direction(state == SpindleState::Cw); } + + // rate adjusted spindles (laser) in M4 set power via the stepper engine, not here + // set_output must go first because of the way enable is used for level // converters on some boards. - set_output(dev_speed); + + if (isRateAdjusted() && (state == SpindleState::Ccw)) { + dev_speed = offSpeed(); + set_output(dev_speed); + } else { + set_output(dev_speed); + } + set_enable(state != SpindleState::Disable); spindleDelay(state, speed); } diff --git a/FluidNC/src/Spindles/Spindle.h b/FluidNC/src/Spindles/Spindle.h index c598186cf..ff05d7d67 100644 --- a/FluidNC/src/Spindles/Spindle.h +++ b/FluidNC/src/Spindles/Spindle.h @@ -46,6 +46,7 @@ namespace Spindles { void stop() { setState(SpindleState::Disable, 0); } virtual void config_message() = 0; virtual bool isRateAdjusted(); + virtual bool use_delay_settings() const { return true; } virtual void setSpeedfromISR(uint32_t dev_speed) = 0; @@ -75,10 +76,13 @@ namespace Spindles { void afterParse() override; void group(Configuration::HandlerBase& handler) override { - handler.item("spinup_ms", _spinup_ms); - handler.item("spindown_ms", _spindown_ms); + if (use_delay_settings()) { + handler.item("spinup_ms", _spinup_ms); + handler.item("spindown_ms", _spindown_ms); + } handler.item("tool", _tool); handler.item("speeds", _speeds); + } // Virtual base classes require a virtual destructor. diff --git a/FluidNC/src/Spindles/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index b7b17a132..49eabe06a 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -23,6 +23,7 @@ #include "../Machine/MachineConfig.h" #include "../MotionControl.h" // mc_reset #include "../Protocol.h" // rtAlarm +#include "../Report.h" // hex message #include #include @@ -38,23 +39,6 @@ namespace Spindles { QueueHandle_t VFD::vfd_cmd_queue = nullptr; TaskHandle_t VFD::vfd_cmdTaskHandle = nullptr; -#if defined(DEBUG_VFD) || defined(DEBUG_VFD_ALL) - // Print a message in hex format - // Example: report_hex_msg(msg, "Rx:", 6); - // would would print something like ... [MSG Rx: 0x01 0x03 0x01 0x08 0x31 0xbf] - void VFD::hex_msg(uint8_t* buf, const char* prefix, int len) { - char report[200]; - char temp[20]; - sprintf(report, "%s", prefix); - for (int i = 0; i < len; i++) { - sprintf(temp, " 0x%02X", buf[i]); - strcat(report, temp); - } - - log_info(report); - } -#endif - void VFD::reportParsingErrors(ModbusCommand cmd, uint8_t* rx_message, size_t read_length) { #ifdef DEBUG_VFD hex_msg(cmd.msg, "RS485 Tx: ", cmd.tx_length); @@ -70,7 +54,7 @@ namespace Spindles { if (rx_message[0] != id) { log_info("RS485 received message from other modbus device"); } else if (read_length != cmd.rx_length) { - log_info("RS485 received message of unexpected length; expected %d, got %d", int(cmd.rx_length), int(read_length)); + log_info("RS485 received message of unexpected length; expected:" << int(cmd.rx_length) << " got:" << int(read_length)); } else { log_info("RS485 CRC check failed"); } @@ -117,6 +101,7 @@ namespace Spindles { next_cmd.critical = action.critical; break; case actionSetMode: + log_debug("vfd_cmd_task mode:" << action.action); if (!instance->prepareSetModeCommand(SpindleState(action.arg), next_cmd)) { continue; // main loop } @@ -254,7 +239,7 @@ namespace Spindles { if (retry_count == MAX_RETRIES) { if (!unresponsive) { - log_info("Spindle RS485 Unresponsive " << next_cmd.rx_length); + log_info("Spindle RS485 Unresponsive"); unresponsive = true; pollidx = -1; } @@ -307,21 +292,14 @@ namespace Spindles { } config_message(); + + set_mode(SpindleState::Disable, true); } // Checks for all the required pin definitions // It returns a message for each missing pin // Returns true if all pins are defined. - bool VFD::get_pins_and_settings() { - bool pins_settings_ok = true; - - if (config->_laserMode) { - log_info("VFD spindle disabled in laser mode. Set $GCode/LaserMode=Off and restart"); - pins_settings_ok = false; - } - - return pins_settings_ok; - } + bool VFD::get_pins_and_settings() { return true; } void VFD::config_message() { _uart->config_message(name(), " Spindle "); } @@ -333,7 +311,7 @@ namespace Spindles { bool critical = (sys.state == State::Cycle || state != SpindleState::Disable); uint32_t dev_speed = mapSpeed(speed); - log_debug("speed " << speed << " dev_speed " << dev_speed); + log_debug("Speed:" << speed << " linearized:" << dev_speed); if (_current_state != state) { // Changing state @@ -347,7 +325,7 @@ namespace Spindles { setSpeed(dev_speed); } } - if (!supports_actual_speed()) { + if (use_delay_settings()) { spindleDelay(state, speed); } else { // _sync_dev_speed is set by a callback that handles @@ -365,7 +343,7 @@ namespace Spindles { while ((_sync_dev_speed < minSpeedAllowed || _sync_dev_speed > maxSpeedAllowed) && unchanged < limit) { #ifdef DEBUG_VFD - log_debug("Syncing speed. Requested %d, current %d", int(dev_speed), int(_sync_dev_speed)); + log_debug("Syncing speed. Requested: " << int(dev_speed) << " current:" << int(_sync_dev_speed)); #endif if (!mc_dwell(500)) { // Something happened while we were dwelling, like a safety door. @@ -379,7 +357,7 @@ namespace Spindles { last = _sync_dev_speed; } #ifdef DEBUG_VFD - log_debug("Synced speed. Requested %d, current %d", int(dev_speed), int(_sync_dev_speed)); + log_debug("Synced speed. Requested:" << int(dev_speed) << " current:" << int(_sync_dev_speed)); #endif if (unchanged == limit) { @@ -409,6 +387,7 @@ namespace Spindles { _current_state = mode; return true; } + void VFD::set_mode(SpindleState mode, bool critical) { if (vfd_cmd_queue) { VFDaction action; @@ -449,7 +428,7 @@ namespace Spindles { _current_dev_speed = speed; #ifdef DEBUG_VFD_ALL - log_debug("Setting spindle speed to %d", int(speed)); + log_debug("Setting spindle speed to:" << int(speed)); #endif // Do variant-specific command preparation set_speed_command(speed, data); diff --git a/FluidNC/src/Spindles/VFDSpindle.h b/FluidNC/src/Spindles/VFDSpindle.h index 9f82c6224..a2c62e7af 100644 --- a/FluidNC/src/Spindles/VFDSpindle.h +++ b/FluidNC/src/Spindles/VFDSpindle.h @@ -35,9 +35,6 @@ namespace Spindles { bool critical; uint32_t arg; }; -#if defined(DEBUG_VFD) || defined(DEBUG_VFD_ALL) - void hex_msg(uint8_t* buf, const char* prefix, int len); -#endif protected: struct ModbusCommand { @@ -67,7 +64,7 @@ namespace Spindles { virtual response_parser get_current_speed(ModbusCommand& data) { return nullptr; } virtual response_parser get_current_direction(ModbusCommand& data) { return nullptr; } virtual response_parser get_status_ok(ModbusCommand& data) = 0; - virtual bool supports_actual_speed() const { return false; } + virtual bool safety_polling() const { return true; } // The constructor sets these diff --git a/FluidNC/src/Spindles/YL620Spindle.cpp b/FluidNC/src/Spindles/YL620Spindle.cpp index 0af7a9ebe..b313fcd27 100644 --- a/FluidNC/src/Spindles/YL620Spindle.cpp +++ b/FluidNC/src/Spindles/YL620Spindle.cpp @@ -132,7 +132,7 @@ namespace Spindles { yl620->_minFrequency = (uint16_t(response[3]) << 8) | uint16_t(response[4]); #ifdef DEBUG_VFD - log_debug("YL620 allows minimum frequency of " << _minFrequency << " Hz"); + log_debug("YL620 allows minimum frequency of:" << yl620->_minFrequency << " Hz"); #endif return true; diff --git a/FluidNC/src/Spindles/YL620Spindle.h b/FluidNC/src/Spindles/YL620Spindle.h index 78659dde1..ad211b171 100644 --- a/FluidNC/src/Spindles/YL620Spindle.h +++ b/FluidNC/src/Spindles/YL620Spindle.h @@ -19,7 +19,7 @@ namespace Spindles { response_parser get_current_direction(ModbusCommand& data) override; response_parser get_status_ok(ModbusCommand& data) override { return nullptr; } - bool supports_actual_speed() const override { return true; } + bool use_delay_settings() const override { return false; } bool safety_polling() const override { return false; } // Name of the configurable. Must match the name registered in the cpp file. diff --git a/FluidNC/src/Stepper.cpp b/FluidNC/src/Stepper.cpp index a914e0a49..0021c31ce 100644 --- a/FluidNC/src/Stepper.cpp +++ b/FluidNC/src/Stepper.cpp @@ -418,7 +418,7 @@ void Stepper::prep_buffer() { // prep.inv_rate is only used if is_pwm_rate_adjusted is true st_prep_block->is_pwm_rate_adjusted = false; // set default value - if (config->_laserMode) { + if (spindle->isRateAdjusted()) { if (pl_block->spindle == SpindleState::Ccw) { // Pre-compute inverse programmed rate to speed up PWM updating per step segment. prep.inv_rate = 1.0f / pl_block->programmed_rate; diff --git a/FluidNC/src/WebUI/JSONEncoder.cpp b/FluidNC/src/WebUI/JSONEncoder.cpp index b2441c15d..80cbff481 100644 --- a/FluidNC/src/WebUI/JSONEncoder.cpp +++ b/FluidNC/src/WebUI/JSONEncoder.cpp @@ -148,13 +148,16 @@ namespace WebUI { // Creates an Esp32_WebUI configuration item specification from // a value passed in as a C-style string. - void JSONencoder::begin_webui(const char* brief, const char* full, const char* type, const char* val) { + void JSONencoder::begin_webui(const char* name, const char* help, const char* type, const char* val) { begin_object(); member("F", "network"); - // We must pass the full path as the P parameter because that is - // what WebUI sends back to us when setting a new value. - member("P", full); - member("H", full); + // P is the name that WebUI uses to set a new value. + // H is the legend that WebUI displays in the UI. + // The distinction used to be important because, prior to the introuction + // of named settings, P was a numerical offset into a fixed EEPROM layout. + // Now P is a hierarchical name that is as easy to understand as the old H values. + member("P", name); + member("H", help); member("T", type); member("V", val); } diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 4109f4ad4..bd4caa331 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -41,17 +41,12 @@ namespace WebUI { enum_opt_t onoffOptions = { { "OFF", 0 }, { "ON", 1 } }; #ifdef ENABLE_WIFI - EnumSetting* wifi_radio_mode; - enum_opt_t wifiModeOptions = { - { "STA", ESP_WIFI_STA }, - { "AP", ESP_WIFI_AP }, - { "STA_AP", ESP_WIFI_STA_AP }, + { "Off", WiFiOff }, + { "STA", WiFiSTA }, + { "AP", WiFiAP }, + { "STA>AP", WiFiFallback }, }; -#endif - -#ifdef ENABLE_WIFI - EnumSetting* wifi_enable; EnumSetting* wifi_mode; StringSetting* wifi_sta_ssid; @@ -641,8 +636,17 @@ namespace WebUI { j.begin(); j.begin_array("EEPROM"); + // NVS settings + for (Setting* js = Setting::List; js; js = js->next()) { + if (js->getType() == WEBSET) { + js->addWebui(&j); + } + } + + // Configuration tree Configuration::JsonGenerator gen(j); config->group(gen); + j.end_array(); j.end(); @@ -1021,29 +1025,53 @@ namespace WebUI { void make_wifi_settings() { #ifdef ENABLE_WIFI - - wifi_mode = new EnumSetting("WiFi mode", WEBSET, WA, "ESP116", "WiFi/Mode", WIFI_AP, &wifiModeOptions, NULL); - wifi_enable = new EnumSetting("Wifi Enable", WEBSET, WA, "ESP117", "WiFi/Enable", 1, &onoffOptions, NULL); + new WebCommand( + "TYPE=NONE|PUSHOVER|EMAIL|LINE T1=token1 T2=token2 TS=settings", WEBCMD, WA, "ESP610", "Notification/Setup", showSetNotification); + notification_ts = new StringSetting( + "Notification Settings", WEBSET, WA, NULL, "Notification/TS", DEFAULT_TOKEN, 0, MAX_NOTIFICATION_SETTING_LENGTH, NULL); + notification_t2 = new StringSetting("Notification Token 2", + WEBSET, + WA, + NULL, + "Notification/T2", + DEFAULT_TOKEN, + MIN_NOTIFICATION_TOKEN_LENGTH, + MAX_NOTIFICATION_TOKEN_LENGTH, + NULL); + notification_t1 = new StringSetting("Notification Token 1", + WEBSET, + WA, + NULL, + "Notification/T1", + DEFAULT_TOKEN, + MIN_NOTIFICATION_TOKEN_LENGTH, + MAX_NOTIFICATION_TOKEN_LENGTH, + NULL); + notification_type = new EnumSetting( + "Notification type", WEBSET, WA, NULL, "Notification/Type", DEFAULT_NOTIFICATION_TYPE, ¬ificationOptions, NULL); + new WebCommand("message", WEBCMD, WU, "ESP600", "Notification/Send", sendMessage); telnet_port = new IntSetting( "Telnet Port", WEBSET, WA, "ESP131", "Telnet/Port", DEFAULT_TELNETSERVER_PORT, MIN_TELNET_PORT, MAX_TELNET_PORT, NULL); telnet_enable = new EnumSetting("Telnet Enable", WEBSET, WA, "ESP130", "Telnet/Enable", DEFAULT_TELNET_STATE, &onoffOptions, NULL); + http_port = - new IntSetting("HTTP Port", WEBSET, WA, "ESP121", "Http/Port", DEFAULT_WEBSERVER_PORT, MIN_HTTP_PORT, MAX_HTTP_PORT, NULL); - http_enable = new EnumSetting("HTTP Enable", WEBSET, WA, "ESP120", "Http/Enable", DEFAULT_HTTP_STATE, &onoffOptions, NULL); + new IntSetting("HTTP Port", WEBSET, WA, "ESP121", "HTTP/Port", DEFAULT_WEBSERVER_PORT, MIN_HTTP_PORT, MAX_HTTP_PORT, NULL); + http_enable = new EnumSetting("HTTP Enable", WEBSET, WA, "ESP120", "HTTP/Enable", DEFAULT_HTTP_STATE, &onoffOptions, NULL); + wifi_hostname = new StringSetting("Hostname", WEBSET, WA, "ESP112", - "System/Hostname", + "Hostname", DEFAULT_HOSTNAME, MIN_HOSTNAME_LENGTH, MAX_HOSTNAME_LENGTH, (bool (*)(char*))WiFiConfig::isHostnameValid); + wifi_ap_channel = new IntSetting("AP Channel", WEBSET, WA, "ESP108", "AP/Channel", DEFAULT_AP_CHANNEL, MIN_CHANNEL, MAX_CHANNEL, NULL); - wifi_ap_ip = new IPaddrSetting("AP Static IP", WEBSET, WA, "ESP107", "AP/IP", DEFAULT_AP_IP, NULL); - // no get, admin to set + wifi_ap_ip = new IPaddrSetting("AP Static IP", WEBSET, WA, "ESP107", "AP/IP", DEFAULT_AP_IP, NULL); wifi_ap_password = new StringSetting("AP Password", WEBSET, WA, @@ -1059,7 +1087,6 @@ namespace WebUI { 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); wifi_sta_mode = new EnumSetting("Station IP Mode", WEBSET, WA, "ESP102", "Sta/IPMode", DEFAULT_STA_IP_MODE, &staModeOptions, NULL); - // no get, admin to set wifi_sta_password = new StringSetting("Station Password", WEBSET, WA, @@ -1079,37 +1106,11 @@ namespace WebUI { MAX_SSID_LENGTH, (bool (*)(char*))WiFiConfig::isSSIDValid); - new WebCommand( - "TYPE=NONE|PUSHOVER|EMAIL|LINE T1=token1 T2=token2 TS=settings", WEBCMD, WA, "ESP610", "Notification/Setup", showSetNotification); - notification_ts = new StringSetting( - "Notification Settings", WEBSET, WA, NULL, "Notification/TS", DEFAULT_TOKEN, 0, MAX_NOTIFICATION_SETTING_LENGTH, NULL); - notification_t2 = new StringSetting("Notification Token 2", - WEBSET, - WA, - NULL, - "Notification/T2", - DEFAULT_TOKEN, - MIN_NOTIFICATION_TOKEN_LENGTH, - MAX_NOTIFICATION_TOKEN_LENGTH, - NULL); - notification_t1 = new StringSetting("Notification Token 1", - WEBSET, - WA, - NULL, - "Notification/T1", - DEFAULT_TOKEN, - MIN_NOTIFICATION_TOKEN_LENGTH, - MAX_NOTIFICATION_TOKEN_LENGTH, - NULL); - notification_type = new EnumSetting( - "Notification type", WEBSET, WA, NULL, "Notification/Type", DEFAULT_NOTIFICATION_TYPE, ¬ificationOptions, NULL); - new WebCommand("message", WEBCMD, WU, "ESP600", "Notification/Send", sendMessage); + wifi_mode = new EnumSetting("WiFi mode", WEBSET, WA, "ESP116", "WiFi/Mode", WiFiFallback, &wifiModeOptions, NULL); new WebCommand(NULL, WEBCMD, WU, "ESP410", "WiFi/ListAPs", listAPs); new WebCommand(NULL, WEBCMD, WG, "ESP111", "System/IP", showIP); new WebCommand("IP=ipaddress MSK=netmask GW=gateway", WEBCMD, WA, "ESP103", "Sta/Setup", showSetStaParams); - // no get, admin to set - #endif } diff --git a/FluidNC/src/WebUI/WebSettings.h b/FluidNC/src/WebUI/WebSettings.h index 37dbf1cf1..3754735c4 100644 --- a/FluidNC/src/WebUI/WebSettings.h +++ b/FluidNC/src/WebUI/WebSettings.h @@ -7,11 +7,12 @@ #include "../Config.h" // ENABLE_* #include "../Settings.h" -//Radio Mode -const int ESP_WIFI_STA = 1; -const int ESP_WIFI_AP = 2; -const int ESP_WIFI_STA_AP = 3; // Tries STA falls back to AP - +enum WiFiStartupMode { + WiFiOff = 0, + WiFiSTA, + WiFiAP, + WiFiFallback, // Try STA and fall back to AP if STA fails +}; namespace WebUI { #ifdef ENABLE_AUTHENTICATION @@ -21,7 +22,6 @@ namespace WebUI { #ifdef ENABLE_WIFI - extern EnumSetting* wifi_enable; extern EnumSetting* wifi_mode; extern EnumSetting* wifi_sta_mode; extern IPaddrSetting* wifi_sta_ip; diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index fe8e3bc16..e5bb8f8a2 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -8,6 +8,7 @@ WebUI::WiFiConfig wifi_config; #ifdef ENABLE_WIFI +# include "../Main.h" // display() # include "Commands.h" // COMMANDS # include "WifiServices.h" # include "WebSettings.h" @@ -235,6 +236,7 @@ namespace WebUI { return false; case WL_CONNECTED: log_info("Connected - IP is " << WiFi.localIP().toString()); + display("IP", WiFi.localIP().toString()); return true; default: if ((dot > 3) || (dot == 0)) { @@ -267,15 +269,16 @@ namespace WebUI { WiFi.softAPdisconnect(); } WiFi.enableAP(false); - WiFi.mode(WIFI_STA); - //Get parameters for STA - String h = wifi_hostname->get(); - WiFi.setHostname(h.c_str()); //SSID String SSID = wifi_sta_ssid->get(); if (SSID.length() == 0) { - SSID = DEFAULT_STA_SSID; + log_info("STA SSID is not set"); + return false; } + WiFi.mode(WIFI_STA); + //Get parameters for STA + String h = wifi_hostname->get(); + WiFi.setHostname(h.c_str()); //password String password = wifi_sta_password->get(); int8_t IP_mode = wifi_sta_mode->get(); @@ -346,6 +349,7 @@ namespace WebUI { //Start AP if (WiFi.softAP(SSID.c_str(), (password.length() > 0) ? password.c_str() : NULL, channel)) { log_info("AP started"); + display("IP", ip.toString()); return true; } @@ -379,23 +383,28 @@ namespace WebUI { //stop active services wifi_services.end(); - if (!wifi_enable->get()) { - log_info("WiFi not enabled"); - return false; - } - - if ((wifi_mode->get() == ESP_WIFI_STA || wifi_mode->get() == ESP_WIFI_STA_AP) && StartSTA()) { - // WIFI mode is STA; fall back on AP if necessary - goto wifi_on; - } - if (wifi_mode->get() == ESP_WIFI_STA_AP) { - log_info("STA connection failed. Setting up AP"); - } - - if ((wifi_mode->get() == ESP_WIFI_AP || wifi_mode->get() == ESP_WIFI_STA_AP) && StartAP()) { - goto wifi_on; - } - + switch (wifi_mode->get()) { + case WiFiOff: + log_info("WiFi is disabled"); + return false; + case WiFiSTA: + if (StartSTA()) { + goto wifi_on; + } + goto wifi_off; + case WiFiFallback: + if (StartSTA()) { + goto wifi_on; + } + // fall through to fallback to AP mode + case WiFiAP: + if (StartAP()) { + goto wifi_on; + } + goto wifi_off; + } + + wifi_off: log_info("WiFi off"); WiFi.mode(WIFI_OFF); return false; diff --git a/FluidNC/src/WebUI/WifiConfig.h b/FluidNC/src/WebUI/WifiConfig.h index 176cb42e6..359b49a34 100644 --- a/FluidNC/src/WebUI/WifiConfig.h +++ b/FluidNC/src/WebUI/WifiConfig.h @@ -42,8 +42,8 @@ namespace WebUI { //defaults values static const char* DEFAULT_HOSTNAME = "fluidnc"; - static const char* DEFAULT_STA_SSID = "FluidNC"; - static const char* DEFAULT_STA_PWD = "12345678"; + static const char* DEFAULT_STA_SSID = ""; + static const char* DEFAULT_STA_PWD = ""; static const char* DEFAULT_STA_IP = "0.0.0.0"; static const char* DEFAULT_STA_GW = "0.0.0.0"; static const char* DEFAULT_STA_MK = "0.0.0.0"; @@ -63,7 +63,7 @@ namespace WebUI { //boundaries static const int MAX_SSID_LENGTH = 32; - static const int MIN_SSID_LENGTH = 1; + static const int MIN_SSID_LENGTH = 0; // Allow null SSIDs as a way to disable static const int MAX_PASSWORD_LENGTH = 64; //min size of password is 0 or upper than 8 char //so let set min is 8 diff --git a/README.md b/README.md index c0a0e47f0..995aba24e 100644 --- a/README.md +++ b/README.md @@ -6,11 +6,11 @@ ## Introduction -**FluidNC** is the next generation of Grbl_ESP32. It has a lot of improvements over Grbl_ESP32 as listed below. +**FluidNC** is the next generation of the Grbl_ESP32 CNC control firmware. It has a lot of improvements over Grbl_ESP32 as listed below. ## Status -We are currently in an alpha testing state. Basic machines are fully functional. We are actively testing the advanced functions and improving the usability. +We are currently in an beta testing state. Basic machines are fully functional. We are actively testing the advanced functions and improving the usability. ## Firmware Architecture @@ -20,9 +20,9 @@ We are currently in an alpha testing state. Basic machines are fully functional. ## Machine Definition Method -Grbl_ESP32 used C preprocessor machine definition files (myMachineDef.h) and config.h to define a machine. Any change required a recompile. The goal with FluidNC is that virtually everyone uses the same compiled firmware and configures it with a structured [YAML](https://github.com/bdring/FluidNC/wiki/YAML-Config-File) text file. That file is dynamically loaded from the local FLASH on ESP32. It can be uploaded via the serial port or Wifi. +Grbl_ESP32 used C preprocessor machine definition files (myMachineDef.h) and config.h to define a machine. Any change required a recompile. The goal with FluidNC is that virtually everyone uses the same compiled firmware and configures it with a configuration file in a simplified YAML format. That file is dynamically loaded from the local FLASH on ESP32. It can be uploaded via the serial port or Wifi. -You can have multiple YAML files stored on the ESP32. The default is config.yaml, but you can change that with $Config/Filename= +You can have multiple config files stored on the ESP32. The default is config.yaml, but you can change that with $Config/Filename= ## Basic Grbl Compatibility @@ -65,9 +65,9 @@ coolant: ## Tuning -Many parameters like accelerations and speeds need to be tuned when setting up a new machine. These values are in the YAML file like everything else, but you can also temporarily change them by sending the YAML hierarchy for that setting as a $ command. Sending $axes/x/acceleration=50 would change the acceleration of the x axis to 50. +Many parameters like accelerations and speeds need to be tuned when setting up a new machine. These values are in the config file like everything else, but you can also temporarily change them by sending the config file hierarchy for that setting as a $ command. Sending $axes/x/acceleration=50 would change the acceleration of the x axis to 50. -The changes are temporary. To make them permanent you would edit the YAML file. You can also save the all of the current changes to the YAML with the $CD= +The changes are temporary. To make them permanent you would edit the config file. You can also save the all of the current changes to the config file with the $CD= You can show the value of an individual parameter by sending its $ name with the =, as: ``` @@ -144,7 +144,7 @@ The original [Grbl](https://github.com/gnea/grbl) is an awesome project by Sunge The Wifi and WebUI is based on [this project.](https://github.com/luc-github/ESP3D-WEBUI) -Mitch Bradley designed and implemented the $name=value settings mechanism. The YAML-format runtime configuration mechanism was spearheaded Mitch Bradley, and designed and implemented by Mitch and Stefan de Bruin. Stefan's mastery of C++ is especially evident in the Class architecture of the configuration mechanism. +Mitch Bradley designed and implemented the $name=value settings mechanism. The config file format runtime configuration mechanism was spearheaded Mitch Bradley, and designed and implemented by Mitch and Stefan de Bruin. Stefan's mastery of C++ is especially evident in the Class architecture of the configuration mechanism. ### Contribute diff --git a/build-release.py b/build-release.py index f481c8433..ab39e86dd 100644 --- a/build-release.py +++ b/build-release.py @@ -76,13 +76,13 @@ def buildFs(pioEnv, verbose=True, extraArgs=None): pioPath = os.path.join('.pio', 'build') - exitCode = buildFs('noradio', verbose=verbose) + exitCode = buildFs('wifi', verbose=verbose) if exitCode != 0: numErrors += 1 else: # Put common/spiffs.bin in the archive obj = 'spiffs.bin' - # zipObj.write(os.path.join(pioPath, 'noradio', obj), os.path.join('common', obj)) + zipObj.write(os.path.join(pioPath, 'wifi', obj), os.path.join('common', obj)) tools = os.path.join(os.path.expanduser('~'),'.platformio','packages','framework-arduinoespressif32','tools') bootloader = 'bootloader_dio_80m.bin' zipObj.write(os.path.join(tools, 'sdk', 'bin', bootloader), os.path.join('common', bootloader)) diff --git a/example_configs/6_pack_TMC2130.yaml b/example_configs/6_pack_TMC2130.yaml index 7b87eb6d5..54106483d 100644 --- a/example_configs/6_pack_TMC2130.yaml +++ b/example_configs/6_pack_TMC2130.yaml @@ -194,7 +194,6 @@ homing_init_lock: false enable_parking_override_control: false deactivate_parking_upon_init: false check_limits_at_init: false -limits_two_switches_on_axis: false disable_laser_during_hold: true use_line_numbers: false PWM: diff --git a/example_configs/6_pack_TMC5160.yaml b/example_configs/6_pack_TMC5160.yaml index ef8c6b68c..4ee91985a 100644 --- a/example_configs/6_pack_TMC5160.yaml +++ b/example_configs/6_pack_TMC5160.yaml @@ -194,7 +194,6 @@ homing_init_lock: false enable_parking_override_control: false deactivate_parking_upon_init: false check_limits_at_init: false -limits_two_switches_on_axis: false disable_laser_during_hold: true use_line_numbers: false PWM: diff --git a/example_configs/6_pack_external_huanyang.yaml b/example_configs/6_pack_external_huanyang.yaml new file mode 100644 index 000000000..56f2bfba4 --- /dev/null +++ b/example_configs/6_pack_external_huanyang.yaml @@ -0,0 +1,173 @@ +board: 6 Pack +name: 6 Pack External XYZ Haunyang +stepping: + engine: I2S_STREAM + idle_ms: 250 + pulse_us: 2 + dir_delay_us: 1 + disable_delay_us: 0 + +axes: + shared_stepper_disable: NO_PIN + x: + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false + homing: + cycle: 2 + positive_direction: false + mpos: 150.000 + feed_rate: 100.000 + seek_rate: 200.000 + debounce_ms: 500 + seek_scaler: 1.100 + feed_scaler: 1.100 + + motor0: + limit_neg: NO_PIN + limit_pos: NO_PIN + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 + standard_stepper: + step: I2SO.2 + direction: I2SO.1 + disable: I2SO.0 + + y: + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false + homing: + cycle: 2 + positive_direction: true + mpos: 150.000 + feed_rate: 100.000 + seek_rate: 200.000 + debounce_ms: 500 + seek_scaler: 1.100 + feed_scaler: 1.100 + + motor0: + limit_neg: NO_PIN + limit_pos: NO_PIN + limit_all: gpio.32:pu + hard_limits: true + pulloff: 1.000 + standard_stepper: + step: I2SO.5 + direction: I2SO.4 + disable: I2SO.7 + + z: + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false + homing: + cycle: 1 + positive_direction: true + mpos: 150.000 + feed_rate: 100.000 + seek_rate: 800.000 + debounce_ms: 500 + seek_scaler: 1.100 + feed_scaler: 1.100 + + motor0: + limit_neg: NO_PIN + limit_pos: NO_PIN + limit_all: gpio.35 + hard_limits: true + pulloff: 1.000 + standard_stepper: + step: I2SO.10 + direction: I2SO.9 + disable: I2SO.8 + +i2so: + bck: gpio.22 + data: gpio.21 + ws: gpio.17 + +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + card_detect: NO_PIN + cs: gpio.5 + +control: + safety_door: NO_PIN + reset: NO_PIN + feed_hold: NO_PIN + cycle_start: NO_PIN + macro0: NO_PIN + macro1: NO_PIN + macro2: NO_PIN + macro3: NO_PIN + +coolant: + flood: NO_PIN + mist: NO_PIN + delay_ms: 0 + +probe: + pin: NO_PIN + check_mode_start: true + +macros: + n0: + n1: + macro0: + macro1: + macro2: + macro3: + +user_outputs: + analog0: NO_PIN + analog1: NO_PIN + analog2: NO_PIN + analog3: NO_PIN + analog_frequency0: 5000 + analog_frequency1: 5000 + analog_frequency2: 5000 + analog_frequency3: 5000 + digital0: NO_PIN + digital1: NO_PIN + digital2: NO_PIN + digital3: NO_PIN + +software_debounce_ms: 0 +laser_mode: false +arc_tolerance: 0.002 +junction_deviation: 0.010 +verbose_errors: false +report_inches: false +homing_init_lock: false +enable_parking_override_control: false +deactivate_parking_upon_init: false +check_limits_at_init: false +limits_two_switches_on_axis: false +disable_laser_during_hold: true +use_line_numbers: false + +Huanyang: + uart: + txd_pin: gpio.26 + rxd_pin: gpio.16 + rts_pin: gpio.4 + baud: 9600 + mode: 8N1 + modbus_id: 1 + spinup_ms: 0 + spindown_ms: 0 + tool: 0 + speeds: 0=0% 0=25% 6000=25% 24000=100% diff --git a/example_configs/TMC2209.yaml b/example_configs/TMC2209.yaml index 9a165677a..eb2696bb4 100644 --- a/example_configs/TMC2209.yaml +++ b/example_configs/TMC2209.yaml @@ -173,7 +173,6 @@ homing_init_lock: false enable_parking_override_control: false deactivate_parking_upon_init: false check_limits_at_init: false -limits_two_switches_on_axis: false disable_laser_during_hold: true use_line_numbers: false PWM: diff --git a/example_configs/test_drive_SD.yaml b/example_configs/test_drive_SD.yaml index 214921a28..598d1e097 100644 --- a/example_configs/test_drive_SD.yaml +++ b/example_configs/test_drive_SD.yaml @@ -90,7 +90,6 @@ homing_init_lock: true enable_parking_override_control: false deactivate_parking_upon_init: false check_limits_at_init: true -limits_two_switches_on_axis: false disable_laser_during_hold: true use_line_numbers: false NoSpindle: diff --git a/example_configs/tmc2209_laser.yaml b/example_configs/tmc2209_laser.yaml index 336e7b5cc..85f284c3c 100644 --- a/example_configs/tmc2209_laser.yaml +++ b/example_configs/tmc2209_laser.yaml @@ -3,7 +3,7 @@ board: "TMC2209 4x DK" stepping: engine: RMT - idle_ms: 250 + idle_ms: 255 dir_delay_us: 1 pulse_us: 2 disable_delay_us: 0 @@ -14,33 +14,41 @@ axes: shared_stepper_disable: gpio.25:high x: - steps_per_mm: 800 - max_rate: 5000 - acceleration: 100 - max_travel: 300 + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false homing: cycle: 1 - mpos: 150 positive_direction: false + mpos: 150.000 feed_rate: 100.000 seek_rate: 200.000 debounce_ms: 500 - + seek_scaler: 1.100 + feed_scaler: 1.100 + motor0: + limit_neg: NO_PIN limit_pos: gpio.35 + limit_all: NO_PIN hard_limits: false pulloff: 1.000 tmc_2209: uart: txd_pin: gpio.22 rxd_pin: gpio.21 + rts_pin: NO_PIN + cts_pin: NO_PIN baud: 115200 mode: 8N1 + addr: 0 r_sense: 0.110 - run_current: 0.500 + run_current: 1.200 hold_current: 0.500 - microsteps: 32 + microsteps: 8 stallguard: 0 stallguardDebugMode: false toff_disable: 0 @@ -54,93 +62,157 @@ axes: disable: NO_PIN motor1: + limit_neg: NO_PIN + limit_pos: NO_PIN + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 null_motor: y: - steps_per_mm: 800 - max_rate: 5000 - acceleration: 100 - max_travel: 300 - + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false homing: cycle: 2 - mpos: 150 positive_direction: false + mpos: 150.000 feed_rate: 100.000 seek_rate: 200.000 debounce_ms: 500 - + seek_scaler: 1.100 + feed_scaler: 1.100 + motor0: limit_neg: NO_PIN limit_pos: gpio.34 limit_all: NO_PIN hard_limits: false - pulloff: 1.00 + pulloff: 1.000 tmc_2209: + addr: 1 + r_sense: 0.110 + run_current: 1.200 + hold_current: 0.500 + microsteps: 8 + stallguard: 0 + stallguardDebugMode: false + toff_disable: 0 + toff_stealthchop: 5 + toff_coolstep: 3 + run_mode: StealthChop + homing_mode: StealthChop + use_enable: false step: gpio.33 direction: gpio.32 - microsteps: 16 - addr: 1 + disable: NO_PIN motor1: + limit_neg: NO_PIN + limit_pos: NO_PIN + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 null_motor: z: - steps_per_mm: 800 - max_rate: 5000 - acceleration: 100 - max_travel: 300 - + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false homing: cycle: 2 - mpos: 150 positive_direction: false + mpos: 150.000 feed_rate: 100.000 seek_rate: 200.000 debounce_ms: 500 - + seek_scaler: 1.100 + feed_scaler: 1.100 + motor0: limit_neg: NO_PIN limit_pos: gpio.39 limit_all: NO_PIN hard_limits: false - pulloff: 1.00 + pulloff: 1.000 tmc_2209: + addr: 2 + r_sense: 0.110 + run_current: 1.200 + hold_current: 0.500 + microsteps: 8 + stallguard: 0 + stallguardDebugMode: false + toff_disable: 0 + toff_stealthchop: 5 + toff_coolstep: 3 + run_mode: StealthChop + homing_mode: StealthChop + use_enable: false step: gpio.2 direction: gpio.14 - addr: 2 + disable: NO_PIN motor1: + limit_neg: NO_PIN + limit_pos: NO_PIN + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 null_motor: - a: - steps_per_mm: 800 - max_rate: 5000 - acceleration: 100 - max_travel: 300 - + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false homing: cycle: 2 - mpos: 150 positive_direction: false + mpos: 150.000 feed_rate: 100.000 seek_rate: 200.000 debounce_ms: 500 - + seek_scaler: 1.100 + feed_scaler: 1.100 + motor0: limit_neg: NO_PIN limit_pos: gpio.36 limit_all: NO_PIN hard_limits: false - pulloff: 1.00 + pulloff: 1.000 tmc_2209: + addr: 3 + r_sense: 0.110 + run_current: 1.200 + hold_current: 0.500 + microsteps: 8 + stallguard: 0 + stallguardDebugMode: false + toff_disable: 0 + toff_stealthchop: 5 + toff_coolstep: 3 + run_mode: StealthChop + homing_mode: StealthChop + use_enable: false step: gpio.16 direction: gpio.15 - addr: 3 + disable: NO_PIN motor1: + limit_neg: NO_PIN + limit_pos: NO_PIN + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 null_motor: + spi: miso: gpio.19 @@ -154,15 +226,14 @@ sdcard: probe: pin: NO_PIN +homing_init_lock: false + Laser: pwm_freq: 5000 output_pin: gpio.4 - enable_pin: NO_PIN - direction_pin: NO_PIN + enable_pin: gpio.12 disable_with_zero_speed: false zero_speed_with_disable: true - spinup_ms: 0 - spindown_ms: 0 tool: 100 speeds: 0=0.000% 255=100.000% \ No newline at end of file diff --git a/git-version.py b/git-version.py index 0cec96c9f..4f1d9df8f 100644 --- a/git-version.py +++ b/git-version.py @@ -3,45 +3,54 @@ # Thank you https://docs.platformio.org/en/latest/projectconf/section_env_build.html ! +gitFail = False try: - tag = ( - subprocess.check_output(["git", "describe", "--tags", "--abbrev=0"], stderr=subprocess.DEVNULL) - .strip() - .decode("utf-8") - ) + subprocess.check_call(["git", "status"], stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL) except: - tag = "v3.0.0" + gitFail = True -grbl_version = tag.replace('v','').rpartition('.')[0] +if gitFail: + tag = "v3.0.x" + rev = " (noGit)" +else: + try: + tag = ( + subprocess.check_output(["git", "describe", "--tags", "--abbrev=0"], stderr=subprocess.DEVNULL) + .strip() + .decode("utf-8") + ) + except: + tag = "v3.0.x" -# Check to see if the head commit exactly matches a tag. -# If so, the revision is "release", otherwise it is BRANCH-COMMIT -try: - subprocess.check_call(["git", "describe", "--tags", "--exact"], stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL) - rev = '' -except: - branchname = ( - subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]) - .strip() - .decode("utf-8") - ) - revision = ( - subprocess.check_output(["git", "rev-parse", "--short", "HEAD"]) - .strip() - .decode("utf-8") - ) - modified = ( - subprocess.check_output(["git", "status", "-uno", "-s"]) - .strip() - .decode("utf-8") - ) - if modified: - dirty = "-dirty" - else: - dirty = "" + # Check to see if the head commit exactly matches a tag. + # If so, the revision is "release", otherwise it is BRANCH-COMMIT + try: + subprocess.check_call(["git", "describe", "--tags", "--exact"], stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL) + rev = '' + except: + branchname = ( + subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]) + .strip() + .decode("utf-8") + ) + revision = ( + subprocess.check_output(["git", "rev-parse", "--short", "HEAD"]) + .strip() + .decode("utf-8") + ) + modified = ( + subprocess.check_output(["git", "status", "-uno", "-s"]) + .strip() + .decode("utf-8") + ) + if modified: + dirty = "-dirty" + else: + dirty = "" - rev = " (%s-%s%s)" % (branchname, revision, dirty) + rev = " (%s-%s%s)" % (branchname, revision, dirty) +grbl_version = tag.replace('v','').rpartition('.')[0] git_info = '%s%s' % (tag, rev) provisional = "FluidNC/src/version.cxx" diff --git a/install_scripts/HOWTO-INSTALL.txt b/install_scripts/HOWTO-INSTALL.txt index fd9bfbd34..521c9c00d 100644 --- a/install_scripts/HOWTO-INSTALL.txt +++ b/install_scripts/HOWTO-INSTALL.txt @@ -1,7 +1,6 @@ -Choose the version that you want - wifi , bt , wifibt , or noradio - and go into that folder +Choose the version that you want - wifi , bt - and go into that folder +If you want wifi+bt or no_radio, you must compile yourself. See the wiki For Windows: Run install-win.bat (Double-click or type 'install-win' in a cmd window) For Linux: Run install-linux.sh (Type 'sh install-linux.sh' in a shell terminal window) For MacOS: Run install-macos.sh (Type 'sh install-macos.sh' in a Terminal window) - - diff --git a/platformio.ini b/platformio.ini index 06ecb6838..7dbdab1d1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -18,7 +18,7 @@ default_envs = wifi ;extra_configs=debug.ini [common_env_data] -lib_deps_builtin = +lib_deps_builtin = EEPROM FS Preferences @@ -27,79 +27,60 @@ lib_deps_builtin = SPIFFS [common] -build_flags = - ;-DMACHINE_FILENAME=test_drive.h ;Remove ";" from the beginning of this line and specify the machine file +build_flags = !python git-version.py -DCORE_DEBUG_LEVEL=0 -Wno-unused-variable -Wno-unused-function - -[env] lib_deps = TMCStepper@>=0.7.0,<1.0.0 + ; thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 +bt_deps = + BluetoothSerial +wifi_deps = + ArduinoOTA + DNSServer + ESPmDNS + Update + WebServer + WiFi + WiFiClientSecure + +[env] platform = espressif32 board = esp32dev framework = arduino upload_speed = 921600 board_build.partitions = min_spiffs.csv monitor_speed = 115200 -monitor_flags = +monitor_flags = --eol=CRLF --echo --filter=esp32_exception_decoder -; The board definition file es32dev.json has 40m for f_flash, but we have -; been using 80m for a long time with no apparent issues +monitor_filters=esp32_exception_decoder board_build.f_flash = 80000000L build_flags = ${common.build_flags} -src_filter = +src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + -<.git/> - - - test_build_project_src = true [env:debug] build_type = debug -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0 +lib_deps = ${common.lib_deps} [env:noradio] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0 +lib_deps = ${common.lib_deps} [env:wifi] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0 - ArduinoOTA - DNSServer - ESPmDNS - Update - WebServer - WiFi - WiFiClientSecure - +lib_deps = ${common.lib_deps} ${common.wifi_deps} build_flags = ${common.build_flags} -DENABLE_WIFI [env:bt] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0 - BluetoothSerial - +lib_deps = ${common.lib_deps} ${common.bt_deps} build_flags = ${common.build_flags} -DENABLE_BLUETOOTH [env:wifibt] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0 - BluetoothSerial - ArduinoOTA - DNSServer - ESPmDNS - Update - WebServer - WiFi - WiFiClientSecure +lib_deps = ${common.lib_deps} ${common.bt_deps} ${common.wifi_deps} build_flags = ${common.build_flags} -DENABLE_BLUETOOTH -DENABLE_WIFI