From 35bba0dfb5bb09c8d670a12acdb132add53921c4 Mon Sep 17 00:00:00 2001 From: MitchBradley Date: Fri, 10 Sep 2021 06:48:07 -1000 Subject: [PATCH 01/46] oled wip --- FluidNC/Custom/oled_basic.cpp | 11 +- FluidNC/src/Control.h | 4 +- FluidNC/src/Custom/oled_basic.cpp | 280 ++++++++++++++++++++++++++++++ FluidNC/src/Machine/Axes.h | 3 +- FluidNC/src/Report.cpp | 6 +- FluidNC/src/Report.h | 3 + FluidNC/src/SDCard.cpp | 2 +- FluidNC/src/SDCard.h | 2 +- platformio.ini | 48 +++-- 9 files changed, 320 insertions(+), 39 deletions(-) create mode 100644 FluidNC/src/Custom/oled_basic.cpp 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/Control.h b/FluidNC/src/Control.h index 5086f0761..e07ddbd6d 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..b8d1c7767 --- /dev/null +++ b/FluidNC/src/Custom/oled_basic.cpp @@ -0,0 +1,280 @@ +#if 1 +// 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! + + Library Infor: + https://github.com/ThingPulse/esp8266-oled-ssd1306 + + + Install to PlatformIO with this typed at the terminal + platformio lib install 2978 + + Add this to your machine definition file + #define DISPLAY_CODE_FILENAME "Custom/oled_basic.cpp" +*/ + +// Include the correct display library + +#include "SSD1306Wire.h" +#include "../Machine/MachineConfig.h" + +#include "WiFi.h" +#include "../WebUI/WebSettings.h" +#include "../SettingsDefinitions.h" +#include "../Report.h" +#include "../Machine/Axes.h" +#include "../Uart.h" +#ifndef OLED_ADDRESS +# define OLED_ADDRESS 0x3c +#endif + +#ifndef OLED_SDA +# define OLED_SDA GPIO_NUM_5 +#endif + +#ifndef OLED_SCL +# define OLED_SCL GPIO_NUM_4 +#endif + +#ifndef OLED_GEOMETRY +# define OLED_GEOMETRY GEOMETRY_128_64 +#endif + +SSD1306Wire display(OLED_ADDRESS, OLED_SDA, OLED_SCL, OLED_GEOMETRY); + +static TaskHandle_t displayUpdateTaskHandle = 0; + +//Radio Mode +const int ESP_RADIO_OFF = 0; +const int ESP_WIFI_STA = 1; +const int ESP_WIFI_AP = 2; +const int ESP_BT = 3; + +// This displays the status of the ESP32 Radios...BT, WiFi, etc +void displayRadioInfo() { + String radio_addr = ""; + String radio_name = ""; + String radio_status = ""; + +#ifdef ENABLE_BLUETOOTH + if (config->_comms->_bluetoothConfig) { + radio_name = String("BT: ") + config->_comms->_bluetoothConfig->_name; + } +#endif +#ifdef ENABLE_WIFI + 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:") + config->_comms->_apConfig->_ssid; + radio_addr = WiFi.softAPIP().toString(); + } +#endif + +#ifdef WIFI_OR_BLUETOOTH + if (WiFi.getMode() == WIFI_MODE_NULL) { + radio_name = "Radio Mode: None"; + } +#else + radio_name = "Radio Mode:Disabled"; +#endif + + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.setFont(ArialMT_Plain_10); + + if (sys.state == State::Alarm) { // print below Alarm: + display.drawString(0, 18, radio_name); + display.drawString(0, 30, radio_addr); + + } else { // print next to status + display.drawString(55, 2, config->_comms->_bluetoothConfig ? radio_name : radio_addr); + } +} +// Here changes begin Here changes begin Here changes begin Here changes begin Here changes begin + +void draw_checkbox(int16_t x, int16_t y, int16_t width, int16_t height, bool checked) { + if (checked) + display.fillRect(x, y, width, height); // If log.0 + else + display.drawRect(x, y, width, height); // If log.1 +} + +void displayDRO() { + uint8_t oled_y_pos; + //float wco[MAX_N_AXIS]; + + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.setFont(ArialMT_Plain_10); + + char axisVal[20]; + + display.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(); + + display.setTextAlignment(TEXT_ALIGN_RIGHT); + + float* print_position = get_mpos(); + if (bits_are_true(status_mask->get(), RtStatus::Position)) { + display.drawString(60, 14, "M Pos"); + } else { + display.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 += ":"; + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.drawString(0, oled_y_pos, axis_letter); // String('X') + ":"); + + display.setTextAlignment(TEXT_ALIGN_RIGHT); + snprintf(axisVal, 20 - 1, "%.3f", print_position[axis]); + display.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()) { + display.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()) { + display.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()) { + display.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()) { + display.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()) { + display.drawString(110, oled_y_pos, "D"); + draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_safetyDoor.get()); + oled_y_pos += 10; + } +} + +void displayUpdate(void* pvParameters) { + TickType_t xLastWakeTime; + const TickType_t xDisplayFrequency = 100; // in ticks (typically ms) + xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time. + + vTaskDelay(2500); + uint16_t sd_file_ticker = 0; + + display.init(); + display.flipScreenVertically(); + + while (true) { + display.clear(); + + String state_string = ""; + + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.setFont(ArialMT_Plain_16); + display.drawString(0, 0, state_name()); + + if (config->_sdCard->get_state() == SDCard::State::BusyPrinting) { + display.clear(); + display.setTextAlignment(TEXT_ALIGN_CENTER); + display.setFont(ArialMT_Plain_10); + state_string = "SD File"; + for (int i = 0; i < sd_file_ticker % 10; i++) { + state_string += "."; + } + sd_file_ticker++; + display.drawString(63, 0, state_string); + + display.drawString(63, 12, config->_sdCard->filename()); + + int progress = config->_sdCard->percent_complete(); + // draw the progress bar + display.drawProgressBar(0, 45, 120, 10, progress); + + // draw the percentage as String + display.setFont(ArialMT_Plain_10); + display.setTextAlignment(TEXT_ALIGN_CENTER); + display.drawString(64, 25, String(progress) + "%"); + + } else if (sys.state == State::Alarm) { + displayRadioInfo(); + } else { + displayDRO(); + displayRadioInfo(); + } + + display.display(); + + vTaskDelayUntil(&xLastWakeTime, xDisplayFrequency); + } +} + +void display_init() { + Uart0 << "Init Basic OLED SDA:gpio." << OLED_SDA << " SCL:gpio." << OLED_SCL; +#if 1 + display.init(); + + + display.flipScreenVertically(); + + display.clear(); + + display.setTextAlignment(TEXT_ALIGN_CENTER); + display.setFont(ArialMT_Plain_10); + + #if 0 + String mach_name = config->_name; + // remove characters from the end until the string fits + while (display.getStringWidth(mach_name) > 128) { + mach_name = mach_name.substring(0, mach_name.length() - 1); + } + display.drawString(63, 0, mach_name); +#else +display.drawString(10, 0, "Hello"); +#endif + + display.display(); +#if 0 + xTaskCreatePinnedToCore(displayUpdate, // task + "displayUpdateTask", // name for task + 4096, // size of task stack + NULL, // parameters + 1, // priority + &displayUpdateTaskHandle, + CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core + // core + ); +#endif +#endif +} +#endif \ No newline at end of file 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/Report.cpp b/FluidNC/src/Report.cpp index b675f8a64..d66bc8956 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -467,7 +467,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++) { @@ -475,7 +475,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"; @@ -650,7 +650,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; diff --git a/FluidNC/src/Report.h b/FluidNC/src/Report.h index e661fd515..a4764f3d3 100644 --- a/FluidNC/src/Report.h +++ b/FluidNC/src/Report.h @@ -103,3 +103,6 @@ extern const char* dataBeginMarker; extern const char* dataEndMarker; #include "MyIOStream.h" + +void mpos_to_wpos(float* position); +const char* state_name(); \ No newline at end of file diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index 9945a3ea9..a88b29abd 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 5b1215931..364b825df 100644 --- a/FluidNC/src/SDCard.h +++ b/FluidNC/src/SDCard.h @@ -76,7 +76,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(); Print& getClient() { return _client; } diff --git a/platformio.ini b/platformio.ini index 06ecb6838..0d1785bbb 100644 --- a/platformio.ini +++ b/platformio.ini @@ -15,10 +15,9 @@ lib_dir = libraries test_dir = FluidNC/test data_dir = FluidNC/data default_envs = wifi -;extra_configs=debug.ini [common_env_data] -lib_deps_builtin = +lib_deps_builtin = EEPROM FS Preferences @@ -27,15 +26,14 @@ 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 = +lib_deps = TMCStepper@>=0.7.0,<1.0.0 platform = espressif32 board = esp32dev @@ -43,34 +41,32 @@ 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 = + TMCStepper@>=0.7.0,<1.0.0 + thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 [env:noradio] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0 +lib_deps = + TMCStepper@>=0.7.0,<1.0.0 + thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 [env:wifi] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.0 +lib_deps = + TMCStepper@>=0.7.0,<1.0.0 ArduinoOTA DNSServer ESPmDNS @@ -78,21 +74,19 @@ lib_deps = WebServer WiFi WiFiClientSecure - + thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 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 +lib_deps = + TMCStepper@>=0.7.0,<1.0.0 BluetoothSerial - + thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 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 +lib_deps = + TMCStepper@>=0.7.0,<1.0.0 BluetoothSerial ArduinoOTA DNSServer @@ -101,5 +95,5 @@ lib_deps = WebServer WiFi WiFiClientSecure - + thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 build_flags = ${common.build_flags} -DENABLE_BLUETOOTH -DENABLE_WIFI From ff9fa9e2abd5b1d2574df868b14847aac9af9574 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 12 Sep 2021 11:30:53 -1000 Subject: [PATCH 02/46] OLED WIP --- FluidNC/src/Custom/oled.h | 3 + FluidNC/src/Custom/oled_basic.cpp | 225 +++++++++++++--------------- FluidNC/src/PinMapper.cpp | 2 + FluidNC/src/Serial.cpp | 11 +- FluidNC/src/WebUI/Serial2Socket.cpp | 4 + FluidNC/src/WebUI/WifiConfig.cpp | 19 +++ 6 files changed, 146 insertions(+), 118 deletions(-) create mode 100644 FluidNC/src/Custom/oled.h diff --git a/FluidNC/src/Custom/oled.h b/FluidNC/src/Custom/oled.h new file mode 100644 index 000000000..c7faab607 --- /dev/null +++ b/FluidNC/src/Custom/oled.h @@ -0,0 +1,3 @@ +#pragma once +#include +extern SSD1306Wire oled; diff --git a/FluidNC/src/Custom/oled_basic.cpp b/FluidNC/src/Custom/oled_basic.cpp index b8d1c7767..cb5a6bf22 100644 --- a/FluidNC/src/Custom/oled_basic.cpp +++ b/FluidNC/src/Custom/oled_basic.cpp @@ -1,4 +1,5 @@ -#if 1 +#define INCLUDE_OLED_DISPLAY +#ifdef INCLUDE_OLED_DISPLAY // Copyright (c) 2020 - Bart Dring // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. @@ -27,53 +28,46 @@ // Include the correct display library -#include "SSD1306Wire.h" -#include "../Machine/MachineConfig.h" - -#include "WiFi.h" -#include "../WebUI/WebSettings.h" -#include "../SettingsDefinitions.h" -#include "../Report.h" -#include "../Machine/Axes.h" -#include "../Uart.h" -#ifndef OLED_ADDRESS -# define OLED_ADDRESS 0x3c -#endif - -#ifndef OLED_SDA -# define OLED_SDA GPIO_NUM_5 -#endif +# include +# include "../Machine/MachineConfig.h" -#ifndef OLED_SCL -# define OLED_SCL GPIO_NUM_4 -#endif +# include "WiFi.h" +# include "../WebUI/WebSettings.h" +# include "../SettingsDefinitions.h" +# include "../Report.h" +# include "../Machine/Axes.h" +# include "../Uart.h" +# ifndef OLED_ADDRESS +# define OLED_ADDRESS 0x3c +# endif -#ifndef OLED_GEOMETRY -# define OLED_GEOMETRY GEOMETRY_128_64 -#endif +# ifndef OLED_SDA +# define OLED_SDA GPIO_NUM_21 +# endif -SSD1306Wire display(OLED_ADDRESS, OLED_SDA, OLED_SCL, OLED_GEOMETRY); +# ifndef OLED_SCL +# define OLED_SCL GPIO_NUM_22 +# endif -static TaskHandle_t displayUpdateTaskHandle = 0; +# ifndef OLED_GEOMETRY +# define OLED_GEOMETRY GEOMETRY_64_48 +# endif +SSD1306Wire oled(OLED_ADDRESS, OLED_SDA, OLED_SCL, OLED_GEOMETRY, I2C_ONE, 400000); -//Radio Mode -const int ESP_RADIO_OFF = 0; -const int ESP_WIFI_STA = 1; -const int ESP_WIFI_AP = 2; -const int ESP_BT = 3; +static TaskHandle_t oledUpdateTaskHandle = 0; // This displays the status of the ESP32 Radios...BT, WiFi, etc -void displayRadioInfo() { +void oledRadioInfo() { String radio_addr = ""; String radio_name = ""; String radio_status = ""; -#ifdef ENABLE_BLUETOOTH +# ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig) { - radio_name = String("BT: ") + config->_comms->_bluetoothConfig->_name; + radio_name = String("BT: ") + config->_comms->_bluetoothConfig->BTname(); } -#endif -#ifdef ENABLE_WIFI +# endif +# ifdef ENABLE_WIFI if ((WiFi.getMode() == WIFI_MODE_STA) || (WiFi.getMode() == WIFI_MODE_APSTA)) { radio_name = "STA: " + WiFi.SSID(); radio_addr = WiFi.localIP().toString(); @@ -81,58 +75,60 @@ void displayRadioInfo() { radio_name = String("AP:") + config->_comms->_apConfig->_ssid; radio_addr = WiFi.softAPIP().toString(); } -#endif +# endif -#ifdef WIFI_OR_BLUETOOTH +# ifdef WIFI_OR_BLUETOOTH if (WiFi.getMode() == WIFI_MODE_NULL) { radio_name = "Radio Mode: None"; } -#else +# else radio_name = "Radio Mode:Disabled"; -#endif +# endif - display.setTextAlignment(TEXT_ALIGN_LEFT); - display.setFont(ArialMT_Plain_10); + oled.setTextAlignment(TEXT_ALIGN_LEFT); + oled.setFont(ArialMT_Plain_10); if (sys.state == State::Alarm) { // print below Alarm: - display.drawString(0, 18, radio_name); - display.drawString(0, 30, radio_addr); + oled.drawString(0, 18, radio_name); + oled.drawString(0, 30, radio_addr); } else { // print next to status - display.drawString(55, 2, config->_comms->_bluetoothConfig ? radio_name : radio_addr); +# ifdef ENABLE_BLUETOOTH + oled.drawString(55, 2, config->_comms->_bluetoothConfig ? radio_name : radio_addr); +# endif } } // Here changes begin Here changes begin Here changes begin Here changes begin Here changes begin void draw_checkbox(int16_t x, int16_t y, int16_t width, int16_t height, bool checked) { if (checked) - display.fillRect(x, y, width, height); // If log.0 + oled.fillRect(x, y, width, height); // If log.0 else - display.drawRect(x, y, width, height); // If log.1 + oled.drawRect(x, y, width, height); // If log.1 } -void displayDRO() { +void oledDRO() { uint8_t oled_y_pos; //float wco[MAX_N_AXIS]; - display.setTextAlignment(TEXT_ALIGN_LEFT); - display.setFont(ArialMT_Plain_10); + oled.setTextAlignment(TEXT_ALIGN_LEFT); + oled.setFont(ArialMT_Plain_10); char axisVal[20]; - display.drawString(80, 14, "L"); // Limit switch + 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(); + auto n_axis = config->_axes->_numberAxis; + auto ctrl_pins = config->_control; + bool prb_pin_state = config->_probe->get_state(); - display.setTextAlignment(TEXT_ALIGN_RIGHT); + oled.setTextAlignment(TEXT_ALIGN_RIGHT); float* print_position = get_mpos(); if (bits_are_true(status_mask->get(), RtStatus::Position)) { - display.drawString(60, 14, "M Pos"); + oled.drawString(60, 14, "M Pos"); } else { - display.drawString(60, 14, "W Pos"); + oled.drawString(60, 14, "W Pos"); mpos_to_wpos(print_position); } @@ -141,12 +137,12 @@ void displayDRO() { String axis_letter = String(Machine::Axes::_names[axis]); axis_letter += ":"; - display.setTextAlignment(TEXT_ALIGN_LEFT); - display.drawString(0, oled_y_pos, axis_letter); // String('X') + ":"); + oled.setTextAlignment(TEXT_ALIGN_LEFT); + oled.drawString(0, oled_y_pos, axis_letter); // String('X') + ":"); - display.setTextAlignment(TEXT_ALIGN_RIGHT); + oled.setTextAlignment(TEXT_ALIGN_RIGHT); snprintf(axisVal, 20 - 1, "%.3f", print_position[axis]); - display.drawString(60, oled_y_pos, axisVal); + 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))); @@ -156,125 +152,120 @@ void displayDRO() { oled_y_pos = 14; if (config->_probe->exists()) { - display.drawString(110, oled_y_pos, "P"); + 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()) { - display.drawString(110, oled_y_pos, "H"); + 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()) { - display.drawString(110, oled_y_pos, "S"); + 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()) { - display.drawString(110, oled_y_pos, "R"); + 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()) { - display.drawString(110, oled_y_pos, "D"); + 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; } } -void displayUpdate(void* pvParameters) { +void oledUpdate(void* pvParameters) { TickType_t xLastWakeTime; - const TickType_t xDisplayFrequency = 100; // in ticks (typically ms) - xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time. + 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; - display.init(); - display.flipScreenVertically(); + oled.init(); + oled.flipScreenVertically(); while (true) { - display.clear(); + oled.clear(); String state_string = ""; - display.setTextAlignment(TEXT_ALIGN_LEFT); - display.setFont(ArialMT_Plain_16); - display.drawString(0, 0, state_name()); + oled.setTextAlignment(TEXT_ALIGN_LEFT); + oled.setFont(ArialMT_Plain_16); + oled.drawString(0, 0, state_name()); if (config->_sdCard->get_state() == SDCard::State::BusyPrinting) { - display.clear(); - display.setTextAlignment(TEXT_ALIGN_CENTER); - display.setFont(ArialMT_Plain_10); + 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++; - display.drawString(63, 0, state_string); + oled.drawString(63, 0, state_string); - display.drawString(63, 12, config->_sdCard->filename()); + oled.drawString(63, 12, config->_sdCard->filename()); int progress = config->_sdCard->percent_complete(); // draw the progress bar - display.drawProgressBar(0, 45, 120, 10, progress); + oled.drawProgressBar(0, 45, 120, 10, progress); // draw the percentage as String - display.setFont(ArialMT_Plain_10); - display.setTextAlignment(TEXT_ALIGN_CENTER); - display.drawString(64, 25, String(progress) + "%"); + oled.setFont(ArialMT_Plain_10); + oled.setTextAlignment(TEXT_ALIGN_CENTER); + oled.drawString(64, 25, String(progress) + "%"); } else if (sys.state == State::Alarm) { - displayRadioInfo(); + oledRadioInfo(); } else { - displayDRO(); - displayRadioInfo(); + oledDRO(); + oledRadioInfo(); } - display.display(); + oled.display(); - vTaskDelayUntil(&xLastWakeTime, xDisplayFrequency); + vTaskDelayUntil(&xLastWakeTime, xOledFrequency); } } void display_init() { - Uart0 << "Init Basic OLED SDA:gpio." << OLED_SDA << " SCL:gpio." << OLED_SCL; -#if 1 - display.init(); + Uart0 << "Init OLED SDA:gpio." << OLED_SDA << " SCL:gpio." << OLED_SCL << '\n'; + oled.init(); + oled.flipScreenVertically(); - display.flipScreenVertically(); + oled.clear(); + oled.setLogBuffer(3, 10); - display.clear(); + oled.setTextAlignment(TEXT_ALIGN_LEFT); - display.setTextAlignment(TEXT_ALIGN_CENTER); - display.setFont(ArialMT_Plain_10); - - #if 0 - String mach_name = config->_name; + // String mach_name = config->_name; + //String mach_name = "Blaster"; // remove characters from the end until the string fits - while (display.getStringWidth(mach_name) > 128) { - mach_name = mach_name.substring(0, mach_name.length() - 1); - } - display.drawString(63, 0, mach_name); -#else -display.drawString(10, 0, "Hello"); -#endif - - display.display(); -#if 0 - xTaskCreatePinnedToCore(displayUpdate, // task - "displayUpdateTask", // name for task + //while (oled.getStringWidth(mach_name) > 64) { + // mach_name = mach_name.substring(0, mach_name.length() - 1); + //} + //oled.drawString(0, 0, ".154"); + oled.fillCircle(32, 24, 10); + + oled.display(); +# if 0 + xTaskCreatePinnedToCore(oledUpdate, // task + "oledUpdateTask", // name for task 4096, // size of task stack NULL, // parameters 1, // priority - &displayUpdateTaskHandle, + &oledUpdateTaskHandle, CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core // core ); -#endif -#endif +# endif } -#endif \ No newline at end of file +#endif diff --git a/FluidNC/src/PinMapper.cpp b/FluidNC/src/PinMapper.cpp index 092caa836..1f443b5f0 100644 --- a/FluidNC/src/PinMapper.cpp +++ b/FluidNC/src/PinMapper.cpp @@ -74,6 +74,7 @@ PinMapper::~PinMapper() { } // Arduino compatibility functions, which basically forward the call to the mapper: +#if 0 void IRAM_ATTR digitalWrite(pinnum_t pin, uint8_t val) { auto thePin = Mapping::instance()._mapping[pin]; if (thePin) { @@ -106,3 +107,4 @@ int IRAM_ATTR digitalRead(pinnum_t pin) { auto thePin = Mapping::instance()._mapping[pin]; return (thePin) ? thePin->read() : 0; } +#endif diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index f8c7bd99b..a4339ffdd 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -57,6 +57,8 @@ #include #include // portMUX_TYPE, TaskHandle_T +#include "Custom/oled.h" + portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED; static TaskHandle_t clientCheckTaskHandle = 0; @@ -260,11 +262,18 @@ 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; + oled.clear(); + oled.println(client->_line); + oled.drawLogBuffer(0, 0); + oled.display(); return client; } else { // Log an error and discard the line if it happens during an SD run diff --git a/FluidNC/src/WebUI/Serial2Socket.cpp b/FluidNC/src/WebUI/Serial2Socket.cpp index cefe10e9f..609c2976d 100644 --- a/FluidNC/src/WebUI/Serial2Socket.cpp +++ b/FluidNC/src/WebUI/Serial2Socket.cpp @@ -2,6 +2,7 @@ // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #include "Serial2Socket.h" +#include "../Custom/oled.h" namespace WebUI { Serial_2_Socket Serial2Socket; @@ -24,6 +25,9 @@ namespace WebUI { _TXbufferSize = 0; _RXbufferSize = 0; _RXbufferpos = 0; + oled.clear(); + oled.fillRect(22, 14, 20, 20); + oled.display(); } void Serial_2_Socket::end() { diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index dd1fa2716..e61bf6d73 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -19,6 +19,8 @@ WebUI::WiFiConfig wifi_config; # include # include +# include "../Custom/oled.h" + namespace WebUI { String WiFiConfig::_hostname = ""; bool WiFiConfig::_events_registered = false; @@ -217,6 +219,20 @@ namespace WebUI { return 2 * (RSSI + 100); } + void display_ip_tail(const IPAddress& ip) { + String ipa = ip.toString(); + auto dotpos = ipa.lastIndexOf('.'); // Last . + dotpos = ipa.substring(0, dotpos).lastIndexOf('.'); // Second to last . + auto tail = ipa.substring(dotpos + 1); + + oled.clear(); + oled.setFont(ArialMT_Plain_16); + oled.drawString(0, 0, tail); + oled.display(); + oled.setFont(ArialMT_Plain_10); + log_info("IP tail" << tail); + } + /* * Connect client to AP */ @@ -234,6 +250,7 @@ namespace WebUI { return false; case WL_CONNECTED: log_info("Connected - IP is " << WiFi.localIP().toString()); + display_ip_tail(WiFi.localIP()); return true; default: if ((dot > 3) || (dot == 0)) { @@ -350,6 +367,8 @@ namespace WebUI { //Start AP if (WiFi.softAP(SSID.c_str(), (password.length() > 0) ? password.c_str() : NULL, channel)) { log_info("AP started"); + display_ip_tail(ip); + return true; } From 9389c6600905c5bd075356a70811f612d13b7b74 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 12 Sep 2021 11:49:53 -1000 Subject: [PATCH 03/46] Fix bt and noradio builds --- FluidNC/src/Machine/Communications.h | 14 +++++++-- FluidNC/src/Main.cpp | 6 +++- FluidNC/src/Report.cpp | 15 ++++++---- FluidNC/src/Serial.cpp | 4 ++- FluidNC/src/WebUI/BTConfig.cpp | 14 ++++----- FluidNC/src/WebUI/BTConfig.h | 43 +++------------------------- FluidNC/src/WebUI/TelnetServer.cpp | 4 +-- FluidNC/src/WebUI/TelnetServer.h | 16 +---------- FluidNC/src/WebUI/WebClient.cpp | 15 ++-------- FluidNC/src/WebUI/WebClient.h | 12 ++------ FluidNC/src/WebUI/WebSettings.cpp | 10 +++++++ 11 files changed, 58 insertions(+), 95 deletions(-) diff --git a/FluidNC/src/Machine/Communications.h b/FluidNC/src/Machine/Communications.h index a949e3aba..ca6b455f4 100644 --- a/FluidNC/src/Machine/Communications.h +++ b/FluidNC/src/Machine/Communications.h @@ -23,17 +23,21 @@ namespace Machine { public: Communications() = default; +#ifdef ENABLE_WIFI bool _telnetEnable = true; int _telnetPort = 23; bool _httpEnable = true; int _httpPort = 80; - String _hostname = "fluidnc"; + String _hostname = "fluidnc"; + WifiAPConfig* _apConfig = nullptr; + WifiSTAConfig* _staConfig = nullptr; +#endif +#ifdef ENABLE_BLUETOOTH WebUI::BTConfig* _bluetoothConfig = nullptr; - WifiAPConfig* _apConfig = nullptr; - WifiSTAConfig* _staConfig = nullptr; +#endif void group(Configuration::HandlerBase& handler) override { #ifdef ENABLE_BLUETOOTH @@ -60,9 +64,13 @@ namespace Machine { } ~Communications() { +#ifdef ENABLE_BLUETOOTH delete _bluetoothConfig; +#endif +#ifdef ENABLE_WIFI delete _apConfig; delete _staConfig; +#endif } }; } diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index ba739bc36..0ac586e52 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -16,10 +16,10 @@ #include "MotionControl.h" #include "Platform.h" -#include "WebUI/WifiConfig.h" #include "WebUI/InputBuffer.h" #ifdef ENABLE_WIFI +# include "WebUI/WifiConfig.h" # include #endif #include @@ -117,10 +117,14 @@ void setup() { config->_probe->init(); } +#ifdef ENABLE_WIFI WebUI::wifi_config.begin(); +#endif +#ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig) { config->_comms->_bluetoothConfig->begin(); } +#endif WebUI::inputBuffer.begin(); } catch (const AssertionFailed& ex) { // This means something is terribly broken: diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index d66bc8956..5629db0ba 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -403,9 +403,11 @@ void report_build_info(const char* line, Print& client) { if (ALLOW_FEED_OVERRIDE_DURING_PROBE_CYCLES) { client << "A"; } +#ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig) { client << "B"; } +#endif client << "S"; if (config->_enableParkingOverrideControl) { client << "R"; @@ -422,19 +424,22 @@ void report_build_info(const char* line, Print& client) { client << "[MSG: Machine: " << config->_name << "]\n"; - String info; - info = WebUI::wifi_config.info(); +#ifdef ENABLE_WIFI + String info = WebUI::wifi_config.info(); if (info.length()) { client << "[MSG: Machine: " << info << "]\n"; ; } +#endif +#ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig) { - info = config->_comms->_bluetoothConfig->info(); - if (info.length()) { - client << "[MSG: Machine: " << info << "]\n"; + String btinfo = config->_comms->_bluetoothConfig->info(); + if (btinfo.length()) { + client << "[MSG: Machine: " << btinfo << "]\n"; ; } } +#endif } // Prints the character string line that was received, which has been pre-parsed, diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index a4339ffdd..b8da276f0 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -288,8 +288,10 @@ InputClient* pollClients() { } } - WebUI::COMMANDS::handle(); // Handles feeding watchdog and ESP restart + WebUI::COMMANDS::handle(); // Handles feeding watchdog and ESP restart +#ifdef ENABLE_WIFI WebUI::wifi_services.handle(); // OTA, web_server, telnet_server polling +#endif return nullptr; } diff --git a/FluidNC/src/WebUI/BTConfig.cpp b/FluidNC/src/WebUI/BTConfig.cpp index fdfaca1e6..2972e3146 100644 --- a/FluidNC/src/WebUI/BTConfig.cpp +++ b/FluidNC/src/WebUI/BTConfig.cpp @@ -1,13 +1,15 @@ // Copyright (c) 2014 Luc Lebosse. All rights reserved. // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. -#include "BTConfig.h" +#ifdef ENABLE_BLUETOOTH + +# include "BTConfig.h" -#include "../Machine/MachineConfig.h" -#include "../Report.h" // CLIENT_* -#include "Commands.h" // COMMANDS +# include "../Machine/MachineConfig.h" +# include "../Report.h" // CLIENT_* +# include "Commands.h" // COMMANDS -#include +# include // SerialBT sends the data over Bluetooth namespace WebUI { @@ -15,8 +17,6 @@ namespace WebUI { } // The instance variable for the BTConfig class is in config->_comms -#ifdef ENABLE_BLUETOOTH - extern "C" { const uint8_t* esp_bt_dev_get_address(void); } diff --git a/FluidNC/src/WebUI/BTConfig.h b/FluidNC/src/WebUI/BTConfig.h index 21a7df20e..7bdce0f29 100644 --- a/FluidNC/src/WebUI/BTConfig.h +++ b/FluidNC/src/WebUI/BTConfig.h @@ -4,46 +4,11 @@ #pragma once -#include "../Configuration/Configurable.h" -#include "../Config.h" // ENABLE_* +#ifdef ENABLE_BLUETOOTH +# include "../Configuration/Configurable.h" +# include "../Config.h" // ENABLE_* -#include - -#ifndef ENABLE_BLUETOOTH -# include - -namespace WebUI { - class BluetoothSerial : public Stream { - public: - BluetoothSerial() = default; - int read() { return -1; }; - // This is hardwired at 512 because the real BluetoothSerial hardwires - // the Rx queue size to 512 and code in Report.cpp subtracts available() - // from that to determine how many characters can be sent. - int available() { return 512; }; - size_t write(uint8_t data) override { return 0; }; - size_t write(const uint8_t* buffer, size_t length) override { return 0; }; - int peek() override { return -1; } - void flush() override {} - }; - extern BluetoothSerial SerialBT; - - class BTConfig : public Configuration::Configurable { - private: - String _btname = ""; - - public: - BTConfig() = default; - void handle() {} - bool begin() { return false; } - void end() {} - bool Is_BT_on() { return false; } - String info() { return String(); } - const String& BTname() const { return _btname; } - void group(Configuration::HandlerBase& handler) override {} - }; -} -#else +# include # include namespace WebUI { diff --git a/FluidNC/src/WebUI/TelnetServer.cpp b/FluidNC/src/WebUI/TelnetServer.cpp index e18b22eac..39f790c8d 100644 --- a/FluidNC/src/WebUI/TelnetServer.cpp +++ b/FluidNC/src/WebUI/TelnetServer.cpp @@ -4,12 +4,12 @@ #include "../Machine/MachineConfig.h" #include "TelnetServer.h" +#ifdef ENABLE_WIFI + namespace WebUI { Telnet_Server telnet_server; } -#ifdef ENABLE_WIFI - # include "WifiServices.h" # include "WifiConfig.h" diff --git a/FluidNC/src/WebUI/TelnetServer.h b/FluidNC/src/WebUI/TelnetServer.h index 956152a08..24a19380b 100644 --- a/FluidNC/src/WebUI/TelnetServer.h +++ b/FluidNC/src/WebUI/TelnetServer.h @@ -6,21 +6,7 @@ #include "../Config.h" // ENABLE_* #include -#ifndef ENABLE_WIFI - -namespace WebUI { - class Telnet_Server : public Stream { - public: - Telnet_Server() = default; - int read() { return -1; } - size_t write(uint8_t* data) override { return 0; } - int peek() override { return -1; } - void flush() override {} - size_t get_rx_buffer_available() { return 0; } - }; - extern Telnet_Server telnet_server; -} -#else +#ifdef ENABLE_WIFI class WiFiServer; class WiFiClient; diff --git a/FluidNC/src/WebUI/WebClient.cpp b/FluidNC/src/WebUI/WebClient.cpp index 6bb72eabd..ecd718651 100644 --- a/FluidNC/src/WebUI/WebClient.cpp +++ b/FluidNC/src/WebUI/WebClient.cpp @@ -1,23 +1,18 @@ // Copyright (c) 2014 Luc Lebosse. All rights reserved. // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. -#include "../Report.h" - #ifdef ENABLE_WIFI +# include "../Report.h" # include "WebClient.h" # include -#endif namespace WebUI { -#ifdef ENABLE_WIFI WebClient::WebClient(WebServer* webserver, bool silent) : _header_sent(false), _silent(silent), _webserver(webserver), _buflen(0) {} -#endif size_t WebClient::write(const uint8_t* buffer, size_t length) { if (_silent) { return length; } -#ifdef ENABLE_WIFI if (!_header_sent) { _webserver->setContentLength(CONTENT_LENGTH_UNKNOWN); _webserver->sendHeader("Content-Type", "text/html"); @@ -37,26 +32,20 @@ namespace WebUI { } } return length; -#else - return 0; -#endif } size_t WebClient::write(uint8_t data) { return write(&data, 1); } void WebClient::flush() { -#ifdef ENABLE_WIFI if (_buflen) { _webserver->sendContent(_buffer, _buflen); _buflen = 0; } -#endif } WebClient::~WebClient() { flush(); -#ifdef ENABLE_WIFI _webserver->sendContent(""); //close connection -#endif } } +#endif diff --git a/FluidNC/src/WebUI/WebClient.h b/FluidNC/src/WebUI/WebClient.h index d3cbe0f24..a75238ffe 100644 --- a/FluidNC/src/WebUI/WebClient.h +++ b/FluidNC/src/WebUI/WebClient.h @@ -10,17 +10,12 @@ #ifdef ENABLE_WIFI class WebServer; -#endif namespace WebUI { class WebClient : public Print { public: -#ifdef ENABLE_WIFI WebClient(WebServer* webserver, bool silent); ~WebClient(); -#else - WebClient() = default; -#endif size_t write(uint8_t data) override; size_t write(const uint8_t* buffer, size_t length) override; @@ -29,13 +24,12 @@ namespace WebUI { bool anyOutput() { return _header_sent; } private: - bool _header_sent; - bool _silent; -#ifdef ENABLE_WIFI + bool _header_sent; + bool _silent; WebServer* _webserver; static const size_t BUFLEN = 1200; char _buffer[BUFLEN]; size_t _buflen; -#endif }; } +#endif diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 155e71932..49e74f1d9 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -523,9 +523,11 @@ namespace WebUI { showWifiStats(); #endif +#ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig) { webPrintln(config->_comms->_bluetoothConfig->info().c_str()); } +#endif webPrint("FW version: FluidNC "); webPrint(GIT_TAG); webPrint(GIT_REV); @@ -850,9 +852,11 @@ namespace WebUI { } #endif +#ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig && config->_comms->_bluetoothConfig->Is_BT_on()) { on = true; } +#endif webPrintln(on ? "ON" : "OFF"); return Error::Ok; @@ -874,9 +878,11 @@ namespace WebUI { wifi_config.StopWiFi(); } #endif +#ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig && config->_comms->_bluetoothConfig->Is_BT_on()) { config->_comms->_bluetoothConfig->end(); } +#endif //if On start proper service if (!on) { @@ -884,14 +890,18 @@ namespace WebUI { return Error::Ok; } +#ifdef ENABLE_WIFI //On if (wifi_config.begin()) { return Error::Ok; } +#endif +#ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig) { config->_comms->_bluetoothConfig->begin(); } +#endif webPrintln("[MSG: Radio is Off]"); return Error::Ok; From 66fb28d74acfcdf8e2c0199f3e7ec70085e92cb5 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 12 Sep 2021 14:39:10 -1000 Subject: [PATCH 04/46] Check SD card after other clients; otherwise it locks out their ? --- FluidNC/src/Serial.cpp | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index b8da276f0..44c1c9bc3 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -217,19 +217,6 @@ void client_init() { } InputClient* pollClients() { - auto sdcard = config->_sdCard; - // _readyNext indicates that input is coming from a file and - // the GCode system is ready for another line. - if (sdcard && sdcard->_readyNext) { - Error res = sdcard->readFileLine(sdClient->_line, InputClient::maxLine); - if (res == Error::Ok) { - sdClient->_out = &sdcard->getClient(); - sdcard->_readyNext = false; - return sdClient; - } - report_status_message(res, sdcard->getClient()); - } - for (auto client : clientq) { auto source = client->_in; int c = source->read(); @@ -293,6 +280,19 @@ InputClient* pollClients() { WebUI::wifi_services.handle(); // OTA, web_server, telnet_server polling #endif + auto sdcard = config->_sdCard; + // _readyNext indicates that input is coming from a file and + // the GCode system is ready for another line. + if (sdcard && sdcard->_readyNext) { + Error res = sdcard->readFileLine(sdClient->_line, InputClient::maxLine); + if (res == Error::Ok) { + sdClient->_out = &sdcard->getClient(); + sdcard->_readyNext = false; + return sdClient; + } + report_status_message(res, sdcard->getClient()); + } + return nullptr; } From 5dba8f34e1fa727e6289be8b45aa4a0e824e5cf4 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 12 Sep 2021 14:40:09 -1000 Subject: [PATCH 05/46] Register Uart and macro clients before configuration so log_ works --- FluidNC/src/Main.cpp | 13 +++++++++---- FluidNC/src/Serial.cpp | 9 --------- FluidNC/src/Serial.h | 2 ++ 3 files changed, 11 insertions(+), 13 deletions(-) diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 0ac586e52..61ea155d5 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -16,6 +16,8 @@ #include "MotionControl.h" #include "Platform.h" +#include "WebUI/TelnetServer.h" +#include "WebUI/Serial2Socket.h" #include "WebUI/InputBuffer.h" #ifdef ENABLE_WIFI @@ -38,6 +40,10 @@ void setup() { WiFi.mode(WIFI_OFF); #endif + // Setup input polling loop after loading the configuration, + // because the polling may depend on the config + client_init(); + display_init(); // Load settings from non-volatile storage @@ -53,10 +59,6 @@ void setup() { bool configOkay = config->load(config_filename->get()); make_user_commands(); - // Setup input polling loop after loading the configuration, - // because the polling may depend on the config - client_init(); - if (configOkay) { log_info("Machine " << config->_name); log_info("Board " << config->_board); @@ -119,10 +121,13 @@ void setup() { #ifdef ENABLE_WIFI WebUI::wifi_config.begin(); + register_client(&WebUI::Serial2Socket); + register_client(&WebUI::telnet_server); #endif #ifdef ENABLE_BLUETOOTH if (config->_comms->_bluetoothConfig) { config->_comms->_bluetoothConfig->begin(); + register_client(&WebUI::SerialBT); } #endif WebUI::inputBuffer.begin(); diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index 44c1c9bc3..edd5cca0e 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -41,8 +41,6 @@ #include "Uart.h" #include "Machine/MachineConfig.h" #include "WebUI/InputBuffer.h" -#include "WebUI/TelnetServer.h" -#include "WebUI/Serial2Socket.h" #include "WebUI/Commands.h" #include "WebUI/WifiServices.h" #include "MotionControl.h" @@ -207,13 +205,6 @@ void register_client(Stream* client_stream) { void client_init() { register_client(&Uart0); // USB Serial register_client(&WebUI::inputBuffer); // Macros -#ifdef ENABLE_WIFI - register_client(&WebUI::Serial2Socket); - register_client(&WebUI::telnet_server); -#endif -#ifdef ENABLE_BT - register_client(&WebUI::SerialBT); -#endif } InputClient* pollClients() { diff --git a/FluidNC/src/Serial.h b/FluidNC/src/Serial.h index 1aceb9d4f..ce208c3c6 100644 --- a/FluidNC/src/Serial.h +++ b/FluidNC/src/Serial.h @@ -78,4 +78,6 @@ class AllClients : public Print { size_t write(const uint8_t* buffer, size_t length) override; }; +void register_client(Stream* client_stream); + extern AllClients allClients; From 97156c77bae2e39c99521e34328111b581ffc037 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sat, 18 Sep 2021 10:41:47 -1000 Subject: [PATCH 06/46] Versioning with file --- FluidNC/src/Main.cpp | 2 +- FluidNC/src/Report.cpp | 4 ++-- FluidNC/src/Report.h | 7 +++++-- FluidNC/src/WebUI/WebSettings.cpp | 10 +++++----- git-version.py | 23 ++++++++++++++++++----- 5 files changed, 31 insertions(+), 15 deletions(-) diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 61ea155d5..e8beff695 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -49,7 +49,7 @@ void setup() { // Load settings from non-volatile storage settings_init(); // requires config - log_info("FluidNC " << GIT_TAG << GIT_REV); + log_info("FluidNC " << git_info); log_info("Compiled with ESP32 SDK:" << ESP.getSdkVersion()); if (!SPIFFS.begin(true)) { diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index 5629db0ba..1706dad60 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -206,7 +206,7 @@ void report_feedback_message(Message message) { // ok to send to all clients #include "Uart.h" // Welcome message void report_init_message(Print& client) { - client << "\r\nGrbl " << GRBL_VERSION << " [FluidNC " << GIT_TAG << GIT_REV << " '$' for help]\n"; + client << "\r\nGrbl " << grbl_version << " [FluidNC " << git_info << " '$' for help]\n"; } // Prints current probe parameters. Upon a probe command, these parameters are updated upon a @@ -391,7 +391,7 @@ void report_gcode_modes(Print& client) { // Prints build info line void report_build_info(const char* line, Print& client) { - client << "[VER:FluidNC " << GIT_TAG << GIT_REV << ":" << line << "]\n"; + client << "[VER:FluidNC " << git_info << ":" << line << "]\n"; client << "[OPT:"; if (config->_coolant->hasMist()) { client << "M"; // TODO Need to deal with M8...it could be disabled diff --git a/FluidNC/src/Report.h b/FluidNC/src/Report.h index a4764f3d3..6ffe6822f 100644 --- a/FluidNC/src/Report.h +++ b/FluidNC/src/Report.h @@ -104,5 +104,8 @@ extern const char* dataEndMarker; #include "MyIOStream.h" -void mpos_to_wpos(float* position); -const char* state_name(); \ No newline at end of file +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/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 49e74f1d9..19677c322 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -14,7 +14,9 @@ #include "../Machine/MachineConfig.h" #include "../Machine/WifiSTAConfig.h" #include "../Configuration/JsonGenerator.h" -#include "../Uart.h" // Uart0.baud +#include "../Uart.h" // Uart0.baud +#include "../Report.h" // git_info + #include "Commands.h" // COMMANDS::wait(1); #include "WifiConfig.h" #include "WebClient.h" @@ -166,8 +168,7 @@ namespace WebUI { static Error showFwInfo(char* parameter, AuthenticationLevel auth_level) { // ESP800 webPrint("FW version: FluidNC "); - webPrint(GIT_TAG); - webPrint(GIT_REV); + webPrint(git_info); // TODO: change grbl-embedded to FluidNC after fixing WebUI webPrint(" # FW target:grbl-embedded # FW HW:"); webPrint(config->_sdCard->get_state() == SDCard::State::NotPresent ? "No SD" : "Direct SD"); @@ -529,8 +530,7 @@ namespace WebUI { } #endif webPrint("FW version: FluidNC "); - webPrint(GIT_TAG); - webPrint(GIT_REV); + webPrint(git_info); webPrintln(""); return Error::Ok; } diff --git a/git-version.py b/git-version.py index 23dd9c279..1dee47591 100644 --- a/git-version.py +++ b/git-version.py @@ -1,10 +1,11 @@ import subprocess +import filecmp, tempfile, shutil, os # Thank you https://docs.platformio.org/en/latest/projectconf/section_env_build.html ! try: tag = ( - subprocess.check_output(["git", "describe", "--tags", "--abbrev=0"]) + subprocess.check_output(["git", "describe", "--tags", "--abbrev=0"], stderr=subprocess.DEVNULL) .strip() .decode("utf-8") ) @@ -12,14 +13,12 @@ tag = "v3.0.0" grbl_version = tag.replace('v','').rpartition('.')[0] -print("-DGIT_TAG='\"%s\"'" % (tag)) -print("-DGRBL_VERSION='\"%s\"'" % (grbl_version)) # 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) - print("-DGIT_REV='\"\"'") + rev = '' except: branchname = ( subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]) @@ -41,4 +40,18 @@ else: dirty = "" - print("-DGIT_REV='\" (%s-%s%s)\"'" % (branchname, revision, dirty)) + rev = " (%s-%s%s)" % (branchname, revision, dirty) + +git_info = '%s%s' % (tag, rev) + +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') + +if not (os.path.exists(final) and filecmp.cmp(provisional, final)): + os.remove(final) + os.rename(provisional, final) +else: + os.remove(provisional) From ed2b6f0808930c4831855703d343d38f92b5a296 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:21:43 -1000 Subject: [PATCH 07/46] The first loads starts in Test drive mode. - Removed the default config.yaml that used IO - Changed name to add "Test Drive" in it. --- FluidNC/data/config.yaml | 91 --------------------------- FluidNC/src/Machine/MachineConfig.cpp | 2 +- 2 files changed, 1 insertion(+), 92 deletions(-) delete mode 100644 FluidNC/data/config.yaml diff --git a/FluidNC/data/config.yaml b/FluidNC/data/config.yaml deleted file mode 100644 index e573eb2c8..000000000 --- a/FluidNC/data/config.yaml +++ /dev/null @@ -1,91 +0,0 @@ -name: "ESP32 Dev Controller V4" -board: "ESP32 Dev Controller V4" - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -homing_init_lock: true - -axes: - shared_stepper_disable: gpio.13:high - - x: - steps_per_mm: 800 - max_rate: 5000 - acceleration: 100 - max_travel: 300 - homing: - cycle: 1 - mpos: 150 - positive_direction: false - feed_rate: 100.000 - seek_rate: 200.000 - debounce_ms: 500 - - motor0: - limit_pos: gpio.17:low:pu - hard_limits: false - pulloff: 1.000 - stepstick: - direction: gpio.14 - step: gpio.12 - - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate: 5000 - acceleration: 100 - max_travel: 300 - - homing: - cycle: 2 - mpos: 150 - positive_direction: false - feed_rate: 100.000 - seek_rate: 200.000 - debounce_ms: 500 - - motor0: - limit_neg: NO_PIN - limit_pos: gpio.4:low:pu - limit_all: NO_PIN - hard_limits: false - pulloff: 1.00 - stepstick: - step: gpio.26 - direction: gpio.15 - - motor1: - limit_neg: NO_PIN - limit_pos: gpio.16:low:pu - limit_all: NO_PIN - hard_limits: false - pulloff: 1.25 - stepstick: - step: gpio.27 - direction: gpio.33 - -comms: - wifi_ap: - ip_address: "192.168.0.1" - ssid: FluidNC - -probe: - pin: gpio.32:low:pu - -PWM: - pwm_freq: 5000 - output_pin: gpio.2:low - zero_speed_with_disable: true - enable_pin: gpio.21 - spinup_ms: 1000 - spindown_ms: 1000 - speeds: 0=0% 1000=100% - tool: 0 - diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index 61c655f4e..a3111b9d2 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -193,7 +193,7 @@ namespace Machine { return filesize; } - char defaultConfig[] = "name: Default\nboard: None\n"; + char defaultConfig[] = "name: Default (Test Drive)\nboard: None\n"; bool MachineConfig::load(const char* filename) { // log_info("Heap size before load config is " << uint32_t(xPortGetFreeHeapSize())); From ddf45031f3891ca18ac1c3bb71e84ef89a7f912c Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:27:08 -1000 Subject: [PATCH 08/46] WIP moved pins around --- FluidNC/src/Machine/SPIBus.cpp | 23 ++++++++++++----------- FluidNC/src/Machine/SPIBus.h | 2 +- FluidNC/src/SDCard.cpp | 13 ++++++++++++- FluidNC/src/SDCard.h | 8 +++++++- 4 files changed, 32 insertions(+), 14 deletions(-) diff --git a/FluidNC/src/Machine/SPIBus.cpp b/FluidNC/src/Machine/SPIBus.cpp index a7b352de6..7e7ed3d35 100644 --- a/FluidNC/src/Machine/SPIBus.cpp +++ b/FluidNC/src/Machine/SPIBus.cpp @@ -8,8 +8,8 @@ namespace Machine { void SPIBus::validate() const { - if (_cs.defined() || _miso.defined() || _mosi.defined() || _sck.defined()) { - Assert(_cs.defined(), "SPI CS pin should be configured once"); + if (_miso.defined() || _mosi.defined() || _sck.defined()) { + //Assert(_cs.defined(), "SPI CS pin should be configured once"); Assert(_miso.defined(), "SPI MISO pin should be configured once"); Assert(_mosi.defined(), "SPI MOSI pin should be configured once"); Assert(_sck.defined(), "SPI SCK pin should be configured once"); @@ -17,12 +17,13 @@ namespace Machine { } void SPIBus::init() { - if (_cs.defined()) { // validation ensures the rest is also defined. - log_info("SPI SCK:" << _sck.name() << " MOSI:" << _mosi.name() << " MISO:" << _miso.name() << " CS:" << _cs.name()); + if (_sck.defined()) { // validation ensures the rest is also defined. + //log_info("SPI SCK:" << _sck.name() << " MOSI:" << _mosi.name() << " MISO:" << _miso.name() << " CS:" << _cs.name()); + log_info("SPI SCK:" << _sck.name() << " MOSI:" << _mosi.name() << " MISO:" << _miso.name()); - _cs.setAttr(Pin::Attr::Output); + //_cs.setAttr(Pin::Attr::Output); - auto csPin = _cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + //auto csPin = _cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto mosiPin = _mosi.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto sckPin = _sck.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto misoPin = _miso.getNative(Pin::Capabilities::Input | Pin::Capabilities::Native); @@ -30,12 +31,12 @@ namespace Machine { // Start the SPI bus with the pins defined here. Once it has been started, // those pins "stick" and subsequent attempts to restart it with defaults // for the miso, mosi, and sck pins are ignored - SPI.begin(sckPin, misoPin, mosiPin, csPin); + SPI.begin(sckPin, misoPin, mosiPin); } } void SPIBus::group(Configuration::HandlerBase& handler) { - handler.item("cs", _cs); + //handler.item("cs", _cs); handler.item("miso", _miso); handler.item("mosi", _mosi); handler.item("sck", _sck); @@ -43,9 +44,9 @@ namespace Machine { // XXX it would be nice to have some way to turn off SPI entirely void SPIBus::afterParse() { - if (_cs.undefined()) { - _cs = Pin::create("gpio.5"); - } + // if (_cs.undefined()) { + // _cs = Pin::create("gpio.5"); + // } if (_miso.undefined()) { _miso = Pin::create("gpio.19"); } diff --git a/FluidNC/src/Machine/SPIBus.h b/FluidNC/src/Machine/SPIBus.h index cbb8d186f..4df6c38d3 100644 --- a/FluidNC/src/Machine/SPIBus.h +++ b/FluidNC/src/Machine/SPIBus.h @@ -11,7 +11,7 @@ namespace Machine { public: SPIBus() = default; - Pin _cs; + //Pin _cs; Pin _miso; Pin _mosi; Pin _sck; diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index a88b29abd..8f574efe2 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -121,16 +121,19 @@ uint32_t SDCard::lineNumber() { // 4. The SD card is not plugged in and we have to discover that by trying to read it. // 5. The SD card is plugged in but its filesystem cannot be read SDCard::State SDCard::test_or_open(bool refresh) { + //log_info("SDCard::test_or_open"); auto spiConfig = config->_spi; if (spiConfig == nullptr) { return SDCard::State::NotPresent; } - auto csPin = spiConfig->_cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + //auto csPin = spiConfig->_cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + auto csPin = config->_sdCard->_cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); //no need to go further if SD detect is not correct if (config->_sdCard->_cardDetect.defined() && !config->_sdCard->_cardDetect.read()) { + log_debug("SD Card not detected"); _state = SDCard::State::NotPresent; return _state; } @@ -182,6 +185,8 @@ const char* SDCard::filename() { void SDCard::init() { static bool init_message = true; // used to show messages only once. + log_info("SD Card CS:" << _cs.name() << " Card Detect:" << _cardDetect.name()); + if (init_message) { _cardDetect.report("SD Card Detect"); init_message = false; @@ -190,6 +195,12 @@ void SDCard::init() { _cardDetect.setAttr(Pin::Attr::Output); } +void SDCard::afterParse() { + if (_cs.undefined()) { + _cs = Pin::create("gpio.5"); + } +} + SDCard::~SDCard() { delete _pImpl; } diff --git a/FluidNC/src/SDCard.h b/FluidNC/src/SDCard.h index 364b825df..3920a1ffc 100644 --- a/FluidNC/src/SDCard.h +++ b/FluidNC/src/SDCard.h @@ -57,6 +57,7 @@ class SDCard : public Configuration::Configurable { State _state; Pin _cardDetect; + Pin _cs; SDCard::State test_or_open(bool refresh); Print& _client; WebUI::AuthenticationLevel _auth_level; @@ -87,8 +88,13 @@ class SDCard : public Configuration::Configurable { // Initializes pins. void init(); + void afterParse() override; + // Configuration handlers. - void group(Configuration::HandlerBase& handler) override { handler.item("card_detect", _cardDetect); } + void group(Configuration::HandlerBase& handler) override { + handler.item("card_detect", _cardDetect); + handler.item("cs", _cs); + } ~SDCard(); }; From f70e08cbab1f116804983406ebd5944777a4e28c Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:27:35 -1000 Subject: [PATCH 09/46] Update SDCard.cpp --- FluidNC/src/SDCard.cpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index 8f574efe2..935561124 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -125,21 +125,23 @@ SDCard::State SDCard::test_or_open(bool refresh) { auto spiConfig = config->_spi; if (spiConfig == nullptr) { + log_info("spiConfig == nullptr"); return SDCard::State::NotPresent; } //auto csPin = spiConfig->_cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); - auto csPin = config->_sdCard->_cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + auto csPin = _cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); //no need to go further if SD detect is not correct if (config->_sdCard->_cardDetect.defined() && !config->_sdCard->_cardDetect.read()) { - log_debug("SD Card not detected"); + log_info("SD Card not detected"); _state = SDCard::State::NotPresent; return _state; } //if busy doing something return state if (_state >= SDCard::State::Busy) { + log_info("SDCard::State::Busy"); return _state; } @@ -154,9 +156,14 @@ SDCard::State SDCard::test_or_open(bool refresh) { //refresh content if card was removed if (SD.begin(csPin, SPI, SPIfreq, "/sd", 2)) { - if (SD.cardSize() > 0) { + log_info("SD.begin"); + if (SD.cardSize() > 0) { _state = SDCard::State::Idle; + } else { + log_info("SD not > 0"); } + } else { + log_info("SD Failed begin"); } return _state; } From 72c895c956d5075e0b6e4170c12495223e33658f Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:29:54 -1000 Subject: [PATCH 10/46] WIP working but hardwired in some areas --- FluidNC/src/Machine/SPIBus.cpp | 9 ++++----- FluidNC/src/Machine/SPIBus.h | 2 +- FluidNC/src/SDCard.cpp | 29 +++++++++++------------------ FluidNC/src/SDCard.h | 3 +-- 4 files changed, 17 insertions(+), 26 deletions(-) diff --git a/FluidNC/src/Machine/SPIBus.cpp b/FluidNC/src/Machine/SPIBus.cpp index 7e7ed3d35..76a98c337 100644 --- a/FluidNC/src/Machine/SPIBus.cpp +++ b/FluidNC/src/Machine/SPIBus.cpp @@ -18,10 +18,9 @@ namespace Machine { void SPIBus::init() { if (_sck.defined()) { // validation ensures the rest is also defined. - //log_info("SPI SCK:" << _sck.name() << " MOSI:" << _mosi.name() << " MISO:" << _miso.name() << " CS:" << _cs.name()); log_info("SPI SCK:" << _sck.name() << " MOSI:" << _mosi.name() << " MISO:" << _miso.name()); - //_cs.setAttr(Pin::Attr::Output); + _cs.setAttr(Pin::Attr::Output); //auto csPin = _cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto mosiPin = _mosi.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); @@ -44,9 +43,9 @@ namespace Machine { // XXX it would be nice to have some way to turn off SPI entirely void SPIBus::afterParse() { - // if (_cs.undefined()) { - // _cs = Pin::create("gpio.5"); - // } + if (_cs.undefined()) { + _cs = Pin::create("gpio.5"); + } if (_miso.undefined()) { _miso = Pin::create("gpio.19"); } diff --git a/FluidNC/src/Machine/SPIBus.h b/FluidNC/src/Machine/SPIBus.h index 4df6c38d3..cbb8d186f 100644 --- a/FluidNC/src/Machine/SPIBus.h +++ b/FluidNC/src/Machine/SPIBus.h @@ -11,7 +11,7 @@ namespace Machine { public: SPIBus() = default; - //Pin _cs; + Pin _cs; Pin _miso; Pin _mosi; Pin _sck; diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index 935561124..b09668b7e 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -121,27 +121,22 @@ uint32_t SDCard::lineNumber() { // 4. The SD card is not plugged in and we have to discover that by trying to read it. // 5. The SD card is plugged in but its filesystem cannot be read SDCard::State SDCard::test_or_open(bool refresh) { - //log_info("SDCard::test_or_open"); auto spiConfig = config->_spi; - if (spiConfig == nullptr) { - log_info("spiConfig == nullptr"); + if (spiConfig == nullptr || _cs.undefined()) { return SDCard::State::NotPresent; } //auto csPin = spiConfig->_cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); - auto csPin = _cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); //no need to go further if SD detect is not correct - if (config->_sdCard->_cardDetect.defined() && !config->_sdCard->_cardDetect.read()) { - log_info("SD Card not detected"); + if (_cardDetect.defined() && !_cardDetect.read()) { _state = SDCard::State::NotPresent; return _state; } //if busy doing something return state if (_state >= SDCard::State::Busy) { - log_info("SDCard::State::Busy"); return _state; } @@ -155,15 +150,10 @@ SDCard::State SDCard::test_or_open(bool refresh) { _state = SDCard::State::NotPresent; //refresh content if card was removed - if (SD.begin(csPin, SPI, SPIfreq, "/sd", 2)) { - log_info("SD.begin"); - if (SD.cardSize() > 0) { + if (SD.begin(GPIO_NUM_5, SPI, SPIfreq, "/sd", 2)) { + if (SD.cardSize() > 0) { _state = SDCard::State::Idle; - } else { - log_info("SD not > 0"); } - } else { - log_info("SD Failed begin"); } return _state; } @@ -192,7 +182,10 @@ const char* SDCard::filename() { void SDCard::init() { static bool init_message = true; // used to show messages only once. - log_info("SD Card CS:" << _cs.name() << " Card Detect:" << _cardDetect.name()); + if (_cs.defined()) { + log_info("SD CS:" << _cs.name() << " Detect:" << _cardDetect.name()); + return; + } if (init_message) { _cardDetect.report("SD Card Detect"); @@ -203,9 +196,9 @@ void SDCard::init() { } void SDCard::afterParse() { - if (_cs.undefined()) { - _cs = Pin::create("gpio.5"); - } + if (_cs.undefined()) { + _cs = Pin::create("gpio.14"); + } } SDCard::~SDCard() { diff --git a/FluidNC/src/SDCard.h b/FluidNC/src/SDCard.h index 3920a1ffc..6a6eff8e6 100644 --- a/FluidNC/src/SDCard.h +++ b/FluidNC/src/SDCard.h @@ -79,6 +79,7 @@ class SDCard : public Configuration::Configurable { Error readFileLine(char* line, int len); float percent_complete(); uint32_t lineNumber(); + void afterParse() override; Print& getClient() { return _client; } WebUI::AuthenticationLevel getAuthLevel() { return _auth_level; } @@ -88,8 +89,6 @@ class SDCard : public Configuration::Configurable { // Initializes pins. void init(); - void afterParse() override; - // Configuration handlers. void group(Configuration::HandlerBase& handler) override { handler.item("card_detect", _cardDetect); From 65ada56ffe99b8d393987a39302dbb6730d484ba Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:30:23 -1000 Subject: [PATCH 11/46] Works now - cs moved to sdcard: --- FluidNC/src/Machine/SPIBus.cpp | 11 ++--------- FluidNC/src/Machine/SPIBus.h | 1 - FluidNC/src/SDCard.cpp | 8 +++++--- 3 files changed, 7 insertions(+), 13 deletions(-) diff --git a/FluidNC/src/Machine/SPIBus.cpp b/FluidNC/src/Machine/SPIBus.cpp index 76a98c337..ffee457b7 100644 --- a/FluidNC/src/Machine/SPIBus.cpp +++ b/FluidNC/src/Machine/SPIBus.cpp @@ -1,5 +1,6 @@ // Copyright (c) 2021 - Stefan de Bruijn // Copyright (c) 2021 - Mitch Bradley +// Copyright (c) 2021 - Bart Dring // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #include "SPIBus.h" @@ -9,7 +10,6 @@ namespace Machine { void SPIBus::validate() const { if (_miso.defined() || _mosi.defined() || _sck.defined()) { - //Assert(_cs.defined(), "SPI CS pin should be configured once"); Assert(_miso.defined(), "SPI MISO pin should be configured once"); Assert(_mosi.defined(), "SPI MOSI pin should be configured once"); Assert(_sck.defined(), "SPI SCK pin should be configured once"); @@ -20,9 +20,6 @@ namespace Machine { if (_sck.defined()) { // validation ensures the rest is also defined. log_info("SPI SCK:" << _sck.name() << " MOSI:" << _mosi.name() << " MISO:" << _miso.name()); - _cs.setAttr(Pin::Attr::Output); - - //auto csPin = _cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto mosiPin = _mosi.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto sckPin = _sck.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto misoPin = _miso.getNative(Pin::Capabilities::Input | Pin::Capabilities::Native); @@ -30,12 +27,11 @@ namespace Machine { // Start the SPI bus with the pins defined here. Once it has been started, // those pins "stick" and subsequent attempts to restart it with defaults // for the miso, mosi, and sck pins are ignored - SPI.begin(sckPin, misoPin, mosiPin); + SPI.begin(sckPin, misoPin, mosiPin); // CS is defined by each device } } void SPIBus::group(Configuration::HandlerBase& handler) { - //handler.item("cs", _cs); handler.item("miso", _miso); handler.item("mosi", _mosi); handler.item("sck", _sck); @@ -43,9 +39,6 @@ namespace Machine { // XXX it would be nice to have some way to turn off SPI entirely void SPIBus::afterParse() { - if (_cs.undefined()) { - _cs = Pin::create("gpio.5"); - } if (_miso.undefined()) { _miso = Pin::create("gpio.19"); } diff --git a/FluidNC/src/Machine/SPIBus.h b/FluidNC/src/Machine/SPIBus.h index cbb8d186f..b2aa2a66a 100644 --- a/FluidNC/src/Machine/SPIBus.h +++ b/FluidNC/src/Machine/SPIBus.h @@ -11,7 +11,6 @@ namespace Machine { public: SPIBus() = default; - Pin _cs; Pin _miso; Pin _mosi; Pin _sck; diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index b09668b7e..4b9006e35 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -149,8 +149,10 @@ SDCard::State SDCard::test_or_open(bool refresh) { _state = SDCard::State::NotPresent; + auto csPin = _cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + //refresh content if card was removed - if (SD.begin(GPIO_NUM_5, SPI, SPIfreq, "/sd", 2)) { + if (SD.begin(csPin, SPI, SPIfreq, "/sd", 2)) { if (SD.cardSize() > 0) { _state = SDCard::State::Idle; } @@ -184,7 +186,6 @@ void SDCard::init() { if (_cs.defined()) { log_info("SD CS:" << _cs.name() << " Detect:" << _cardDetect.name()); - return; } if (init_message) { @@ -192,12 +193,13 @@ void SDCard::init() { init_message = false; } + _cs.setAttr(Pin::Attr::Output); _cardDetect.setAttr(Pin::Attr::Output); } void SDCard::afterParse() { if (_cs.undefined()) { - _cs = Pin::create("gpio.14"); + _cs = Pin::create("gpio.5"); } } From a53b696c302e3adc989dd41a6847ab9411db575f Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:31:46 -1000 Subject: [PATCH 12/46] WIP removing default SPI - Need to make sure TMC SPI Stepper check for SPI --- FluidNC/data/TMC2130_pen.yaml | 31 +++++++++++++++++++++++++++++++ FluidNC/src/Machine/SPIBus.cpp | 23 +++++++++++++---------- FluidNC/src/Machine/SPIBus.h | 4 ++++ FluidNC/src/SDCard.cpp | 14 +++++++++----- platformio.ini | 3 ++- 5 files changed, 59 insertions(+), 16 deletions(-) create mode 100644 FluidNC/data/TMC2130_pen.yaml diff --git a/FluidNC/data/TMC2130_pen.yaml b/FluidNC/data/TMC2130_pen.yaml new file mode 100644 index 000000000..be934ef99 --- /dev/null +++ b/FluidNC/data/TMC2130_pen.yaml @@ -0,0 +1,31 @@ +name: "TMC2130 Pen/Laser" +board: "TMC2130 Pen/Laser" + +stepping: + engine: RMT + idle_ms: 255 + dir_delay_us: 1 + pulse_us: 2 + disable_delay_us: 0 + +axes: + shared_stepper_disable: gpio.13:high + +spi: + miso: NO_PIN + mosi: NO_PIN + sck: NO_PIN + +coolant: + flood: NO_PIN + mist: NO_PIN + +comms: + wifi_ap: + ip_address: "192.168.0.1" + ssid: FluidNC + +probe: + pin: NO_PIN + + diff --git a/FluidNC/src/Machine/SPIBus.cpp b/FluidNC/src/Machine/SPIBus.cpp index ffee457b7..04b354d5b 100644 --- a/FluidNC/src/Machine/SPIBus.cpp +++ b/FluidNC/src/Machine/SPIBus.cpp @@ -27,7 +27,8 @@ namespace Machine { // Start the SPI bus with the pins defined here. Once it has been started, // those pins "stick" and subsequent attempts to restart it with defaults // for the miso, mosi, and sck pins are ignored - SPI.begin(sckPin, misoPin, mosiPin); // CS is defined by each device + SPI.begin(sckPin, misoPin, mosiPin); // CS is defined by each device + _defined = true; } } @@ -39,14 +40,16 @@ namespace Machine { // XXX it would be nice to have some way to turn off SPI entirely void SPIBus::afterParse() { - if (_miso.undefined()) { - _miso = Pin::create("gpio.19"); - } - if (_mosi.undefined()) { - _mosi = Pin::create("gpio.23"); - } - if (_sck.undefined()) { - _sck = Pin::create("gpio.18"); - } + // if (_miso.undefined()) { + // _miso = Pin::create("gpio.19"); + // } + // if (_mosi.undefined()) { + // _mosi = Pin::create("gpio.23"); + // } + // if (_sck.undefined()) { + // _sck = Pin::create("gpio.18"); + // } } + + bool SPIBus::defined() { return _defined; } } diff --git a/FluidNC/src/Machine/SPIBus.h b/FluidNC/src/Machine/SPIBus.h index b2aa2a66a..9b388fca1 100644 --- a/FluidNC/src/Machine/SPIBus.h +++ b/FluidNC/src/Machine/SPIBus.h @@ -21,6 +21,10 @@ namespace Machine { void init(); + bool defined(); + ~SPIBus() = default; + private: + bool _defined = false; }; } diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index 4b9006e35..f9b878c7e 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -123,11 +123,15 @@ uint32_t SDCard::lineNumber() { SDCard::State SDCard::test_or_open(bool refresh) { auto spiConfig = config->_spi; - if (spiConfig == nullptr || _cs.undefined()) { + if (spiConfig == nullptr || !spiConfig->defined()) { + log_debug("SPI not defined"); return SDCard::State::NotPresent; } - //auto csPin = spiConfig->_cs.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + if (spiConfig == nullptr || _cs.undefined()) { + log_debug("SD cs not defined"); + return SDCard::State::NotPresent; + } //no need to go further if SD detect is not correct if (_cardDetect.defined() && !_cardDetect.read()) { @@ -198,9 +202,9 @@ void SDCard::init() { } void SDCard::afterParse() { - if (_cs.undefined()) { - _cs = Pin::create("gpio.5"); - } + // if (_cs.undefined()) { + // _cs = Pin::create("gpio.5"); + // } } SDCard::~SDCard() { diff --git a/platformio.ini b/platformio.ini index 0d1785bbb..d08efcc94 100644 --- a/platformio.ini +++ b/platformio.ini @@ -14,7 +14,8 @@ include_dir = FluidNC lib_dir = libraries test_dir = FluidNC/test data_dir = FluidNC/data -default_envs = wifi +default_envs = noradio +;extra_configs=debug.ini [common_env_data] lib_deps_builtin = From 576fab463a222075b1d635c30e7e9b790812389a Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:33:20 -1000 Subject: [PATCH 13/46] Wip stash --- FluidNC/data/15.yaml | 180 +++++++++++++++++++++++++++++++++++++++++ FluidNC/src/Report.cpp | 16 +++- platformio.ini | 2 +- 3 files changed, 196 insertions(+), 2 deletions(-) create mode 100644 FluidNC/data/15.yaml diff --git a/FluidNC/data/15.yaml b/FluidNC/data/15.yaml new file mode 100644 index 000000000..3d1ad3210 --- /dev/null +++ b/FluidNC/data/15.yaml @@ -0,0 +1,180 @@ +board: "Test" +name: "Test" +stepping: + engine: I2S_stream + idle_ms: 250 + pulse_us: 4 + dir_delay_us: 0 + disable_delay_us: 0 + +axes: + shared_stepper_disable: gpio.13:low + x: + steps_per_mm: 800.000 + max_rate: 2000.000 + acceleration: 25.000 + max_travel: 200.000 + soft_limits: false + motor0: + limit_neg: NO_PIN + limit_pos: gpio.18 + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 + stepstick: + step: I2SO.13 + direction: I2SO.12 + disable: NO_PIN + ms1: NO_PIN + ms2: NO_PIN + ms3: NO_PIN + reset: NO_PIN + + y: + steps_per_mm: 800.000 + max_rate: 2000.000 + acceleration: 25.000 + max_travel: 200.000 + soft_limits: false + motor0: + limit_neg: NO_PIN + limit_pos: gpio.23 + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 + stepstick: + step: I2SO.10 + direction: I2SO.5 + disable: NO_PIN + ms1: NO_PIN + ms2: NO_PIN + ms3: NO_PIN + reset: NO_PIN + + z: + steps_per_mm: 800.000 + max_rate: 2000.000 + acceleration: 25.000 + max_travel: 200.000 + soft_limits: false + motor0: + limit_neg: NO_PIN + limit_pos: gpio.19 + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 + stepstick: + step: I2SO.4 + direction: I2SO.3 + disable: NO_PIN + ms1: NO_PIN + ms2: NO_PIN + ms3: NO_PIN + reset: NO_PIN + + a: + steps_per_mm: 800.000 + max_rate: 2000.000 + acceleration: 25.000 + max_travel: 200.000 + soft_limits: false + motor0: + limit_neg: NO_PIN + limit_pos: gpio.22 + limit_all: NO_PIN + hard_limits: true + pulloff: 1.000 + stepstick: + step: I2SO.2 + direction: I2SO.1 + disable: NO_PIN + ms1: NO_PIN + ms2: NO_PIN + ms3: NO_PIN + reset: NO_PIN + +i2so: + bck: gpio.2 + data: gpio.15 + ws: gpio.14 + +spi: + miso: NO_PIN + mosi: NO_PIN + sck: NO_PIN + +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: I2SO.11 + mist: I2SO.15 + delay_ms: 0 + +probe: + pin: NO_PIN + check_mode_start: true + +comms: + telnet_enable: true + telnet_port: 23 + http_enable: true + http_port: 80 + hostname: fluidnc + wifi_ap: + ssid: FluidNC + ip_address: 10.0.0.1 + gateway: 10.0.0.1 + netmask: 255.255.0.0 + dhcp: true + channel: 1 + wifi_sta: + ssid: Barts-WLAN + +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 + +sdcard: + cs: gpio.5 + card_detect: 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: 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/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index 1706dad60..a8540a823 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -206,7 +206,21 @@ void report_feedback_message(Message message) { // ok to send to all clients #include "Uart.h" // Welcome message void report_init_message(Print& client) { - client << "\r\nGrbl " << grbl_version << " [FluidNC " << git_info << " '$' for help]\n"; + client << "\r\nGrbl " << grbl_version << " [FluidNC " << git_info; + +#if defined(ENABLE_WIFI) || defined(ENABLE_BLUETOOTH) +# ifdef ENABLE_WIFI + client << "wifi"; +# endif + +# ifdef ENABLE_BLUETOOTH + client << "bt"; +# endif +#else + client << "noradio"; +#endif + + client << ") '$' for help]\n"; } // Prints current probe parameters. Upon a probe command, these parameters are updated upon a diff --git a/platformio.ini b/platformio.ini index d08efcc94..6bdf3b15b 100644 --- a/platformio.ini +++ b/platformio.ini @@ -14,7 +14,7 @@ include_dir = FluidNC lib_dir = libraries test_dir = FluidNC/test data_dir = FluidNC/data -default_envs = noradio +default_envs = wifi ;extra_configs=debug.ini [common_env_data] From c0c4540ae38c1624030651540c201726334aed32 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:33:58 -1000 Subject: [PATCH 14/46] WIP made sure SPI users can deal with undefined SPI - Fixed some messages - Fixed config files that would be broken --- FluidNC/data/15.yaml | 180 ---------------------- FluidNC/data/TMC2130_pen.yaml | 31 ---- FluidNC/src/Configuration/ParserHandler.h | 2 +- FluidNC/src/Machine/MachineConfig.cpp | 2 +- FluidNC/src/Machine/SPIBus.cpp | 5 +- FluidNC/src/Main.cpp | 2 +- FluidNC/src/Motors/TrinamicDriver.cpp | 13 +- FluidNC/src/SDCard.cpp | 14 +- FluidNC/src/SDCard.h | 2 +- example_configs/3axis_DAC.yaml | 111 ------------- example_configs/3axis_v4.yaml | 60 +++++--- example_configs/6_pack_TMC2130.yaml | 8 +- example_configs/6_pack_TMC5160.yaml | 8 +- example_configs/TMC2130_pen.yaml | 9 ++ example_configs/TMC2209.yaml | 8 +- example_configs/dac.yaml | 119 -------------- example_configs/test_drive_SD.yaml | 98 ++++++++++++ example_configs/tmc2209_10V.yaml | 9 ++ example_configs/tmc2209_BESC.yaml | 9 ++ example_configs/tmc2209_huanyang.yml | 9 ++ example_configs/tmc2209_laser.yaml | 9 ++ example_configs/tmc2209_relay.yaml | 9 ++ 22 files changed, 225 insertions(+), 492 deletions(-) delete mode 100644 FluidNC/data/15.yaml delete mode 100644 FluidNC/data/TMC2130_pen.yaml delete mode 100644 example_configs/3axis_DAC.yaml delete mode 100644 example_configs/dac.yaml create mode 100644 example_configs/test_drive_SD.yaml diff --git a/FluidNC/data/15.yaml b/FluidNC/data/15.yaml deleted file mode 100644 index 3d1ad3210..000000000 --- a/FluidNC/data/15.yaml +++ /dev/null @@ -1,180 +0,0 @@ -board: "Test" -name: "Test" -stepping: - engine: I2S_stream - idle_ms: 250 - pulse_us: 4 - dir_delay_us: 0 - disable_delay_us: 0 - -axes: - shared_stepper_disable: gpio.13:low - x: - steps_per_mm: 800.000 - max_rate: 2000.000 - acceleration: 25.000 - max_travel: 200.000 - soft_limits: false - motor0: - limit_neg: NO_PIN - limit_pos: gpio.18 - limit_all: NO_PIN - hard_limits: true - pulloff: 1.000 - stepstick: - step: I2SO.13 - direction: I2SO.12 - disable: NO_PIN - ms1: NO_PIN - ms2: NO_PIN - ms3: NO_PIN - reset: NO_PIN - - y: - steps_per_mm: 800.000 - max_rate: 2000.000 - acceleration: 25.000 - max_travel: 200.000 - soft_limits: false - motor0: - limit_neg: NO_PIN - limit_pos: gpio.23 - limit_all: NO_PIN - hard_limits: true - pulloff: 1.000 - stepstick: - step: I2SO.10 - direction: I2SO.5 - disable: NO_PIN - ms1: NO_PIN - ms2: NO_PIN - ms3: NO_PIN - reset: NO_PIN - - z: - steps_per_mm: 800.000 - max_rate: 2000.000 - acceleration: 25.000 - max_travel: 200.000 - soft_limits: false - motor0: - limit_neg: NO_PIN - limit_pos: gpio.19 - limit_all: NO_PIN - hard_limits: true - pulloff: 1.000 - stepstick: - step: I2SO.4 - direction: I2SO.3 - disable: NO_PIN - ms1: NO_PIN - ms2: NO_PIN - ms3: NO_PIN - reset: NO_PIN - - a: - steps_per_mm: 800.000 - max_rate: 2000.000 - acceleration: 25.000 - max_travel: 200.000 - soft_limits: false - motor0: - limit_neg: NO_PIN - limit_pos: gpio.22 - limit_all: NO_PIN - hard_limits: true - pulloff: 1.000 - stepstick: - step: I2SO.2 - direction: I2SO.1 - disable: NO_PIN - ms1: NO_PIN - ms2: NO_PIN - ms3: NO_PIN - reset: NO_PIN - -i2so: - bck: gpio.2 - data: gpio.15 - ws: gpio.14 - -spi: - miso: NO_PIN - mosi: NO_PIN - sck: NO_PIN - -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: I2SO.11 - mist: I2SO.15 - delay_ms: 0 - -probe: - pin: NO_PIN - check_mode_start: true - -comms: - telnet_enable: true - telnet_port: 23 - http_enable: true - http_port: 80 - hostname: fluidnc - wifi_ap: - ssid: FluidNC - ip_address: 10.0.0.1 - gateway: 10.0.0.1 - netmask: 255.255.0.0 - dhcp: true - channel: 1 - wifi_sta: - ssid: Barts-WLAN - -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 - -sdcard: - cs: gpio.5 - card_detect: 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: 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/FluidNC/data/TMC2130_pen.yaml b/FluidNC/data/TMC2130_pen.yaml deleted file mode 100644 index be934ef99..000000000 --- a/FluidNC/data/TMC2130_pen.yaml +++ /dev/null @@ -1,31 +0,0 @@ -name: "TMC2130 Pen/Laser" -board: "TMC2130 Pen/Laser" - -stepping: - engine: RMT - idle_ms: 255 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -axes: - shared_stepper_disable: gpio.13:high - -spi: - miso: NO_PIN - mosi: NO_PIN - sck: NO_PIN - -coolant: - flood: NO_PIN - mist: NO_PIN - -comms: - wifi_ap: - ip_address: "192.168.0.1" - ssid: FluidNC - -probe: - pin: NO_PIN - - diff --git a/FluidNC/src/Configuration/ParserHandler.h b/FluidNC/src/Configuration/ParserHandler.h index 6e50920c4..787e00b51 100644 --- a/FluidNC/src/Configuration/ParserHandler.h +++ b/FluidNC/src/Configuration/ParserHandler.h @@ -68,7 +68,7 @@ namespace Configuration { } if (_parser.token_.state == TokenState::Matching) { - log_error("Ignored key " << _parser.key().str()); + log_warn("Ignored key " << _parser.key().str()); } #ifdef DEBUG_CHATTY_YAML_PARSER if (_parser.token_.state == Configuration::TokenState::Matched) { diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index a3111b9d2..253aeedd5 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -36,6 +36,7 @@ namespace Machine { handler.section("axes", _axes); handler.section("i2so", _i2so); handler.section("spi", _spi); + handler.section("sdcard", _sdCard); handler.section("control", _control); handler.section("coolant", _coolant); handler.section("probe", _probe); @@ -43,7 +44,6 @@ namespace Machine { handler.section("macros", _macros); handler.section("user_outputs", _userOutputs); - handler.section("sdcard", _sdCard); handler.item("software_debounce_ms", _softwareDebounceMs); // TODO: Consider putting these under a gcode: hierarchy level? Or motion control? handler.item("laser_mode", _laserMode); diff --git a/FluidNC/src/Machine/SPIBus.cpp b/FluidNC/src/Machine/SPIBus.cpp index 04b354d5b..d6d2951f3 100644 --- a/FluidNC/src/Machine/SPIBus.cpp +++ b/FluidNC/src/Machine/SPIBus.cpp @@ -17,7 +17,7 @@ namespace Machine { } void SPIBus::init() { - if (_sck.defined()) { // validation ensures the rest is also defined. + if (_miso.defined() || _mosi.defined() || _sck.defined()) { // validation ensures the rest is also defined. log_info("SPI SCK:" << _sck.name() << " MOSI:" << _mosi.name() << " MISO:" << _miso.name()); auto mosiPin = _mosi.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); @@ -29,6 +29,9 @@ namespace Machine { // for the miso, mosi, and sck pins are ignored SPI.begin(sckPin, misoPin, mosiPin); // CS is defined by each device _defined = true; + } else { + _defined = false; + log_info("SPI not defined"); } } diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index e8beff695..7cc83333e 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -133,7 +133,7 @@ void setup() { WebUI::inputBuffer.begin(); } catch (const AssertionFailed& ex) { // This means something is terribly broken: - log_info("Critical error in main_init: " << ex.what()); + log_error("Critical error in main_init: " << ex.what()); sys.state = State::ConfigAlarm; } } diff --git a/FluidNC/src/Motors/TrinamicDriver.cpp b/FluidNC/src/Motors/TrinamicDriver.cpp index 5932a8348..f220c41c7 100644 --- a/FluidNC/src/Motors/TrinamicDriver.cpp +++ b/FluidNC/src/Motors/TrinamicDriver.cpp @@ -19,7 +19,10 @@ namespace MotorDrivers { uint8_t daisy_chain_cs = -1; void TrinamicDriver::init() { - _has_errors = false; + _has_errors = false; + auto spiConfig = config->_spi; + + Assert(spiConfig->defined(), "SPI bus is not configured. Cannot initialize TMC driver."); _cs_pin.setAttr(Pin::Attr::Output | Pin::Attr::InitialOn); _cs_mapping = PinMapper(_cs_pin); @@ -57,8 +60,7 @@ namespace MotorDrivers { config_message(); - auto spiConfig = config->_spi; - if (spiConfig != nullptr) { + if (spiConfig != nullptr || !spiConfig->defined()) { auto csPin = _cs_pin.getNative(Pin::Capabilities::Output); auto mosiPin = spiConfig->_mosi.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); auto sckPin = spiConfig->_sck.getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); @@ -96,9 +98,8 @@ namespace MotorDrivers { This is the startup message showing the basic definition */ void TrinamicDriver::config_message() { - log_info(" Trinamic TMC" << _driver_part_number << " Step:" << _step_pin.name() << " Dir:" << _dir_pin.name() - << " CS:" << _cs_pin.name() << " Disable:" << _disable_pin.name() << " Index:" << _spi_index - << " R:" << _r_sense); + log_info(" Trinamic TMC" << _driver_part_number << " Step:" << _step_pin.name() << " Dir:" << _dir_pin.name() << " CS:" + << _cs_pin.name() << " Disable:" << _disable_pin.name() << " Index:" << _spi_index << " R:" << _r_sense); } bool TrinamicDriver::test() { diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index f9b878c7e..2631650d5 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -124,12 +124,12 @@ SDCard::State SDCard::test_or_open(bool refresh) { auto spiConfig = config->_spi; if (spiConfig == nullptr || !spiConfig->defined()) { - log_debug("SPI not defined"); + //log_debug("SPI not defined"); return SDCard::State::NotPresent; } if (spiConfig == nullptr || _cs.undefined()) { - log_debug("SD cs not defined"); + //log_debug("SD cs not defined"); return SDCard::State::NotPresent; } @@ -188,13 +188,13 @@ const char* SDCard::filename() { void SDCard::init() { static bool init_message = true; // used to show messages only once. - if (_cs.defined()) { - log_info("SD CS:" << _cs.name() << " Detect:" << _cardDetect.name()); - } - - if (init_message) { + if (!config->_spi->defined()) { + log_error("SD needs SPI defined"); + } else { + if (init_message) { _cardDetect.report("SD Card Detect"); init_message = false; + } } _cs.setAttr(Pin::Attr::Output); diff --git a/FluidNC/src/SDCard.h b/FluidNC/src/SDCard.h index 6a6eff8e6..2e4db76fe 100644 --- a/FluidNC/src/SDCard.h +++ b/FluidNC/src/SDCard.h @@ -91,8 +91,8 @@ class SDCard : public Configuration::Configurable { // Configuration handlers. void group(Configuration::HandlerBase& handler) override { - handler.item("card_detect", _cardDetect); handler.item("cs", _cs); + handler.item("card_detect", _cardDetect); } ~SDCard(); diff --git a/example_configs/3axis_DAC.yaml b/example_configs/3axis_DAC.yaml deleted file mode 100644 index 67701d2a7..000000000 --- a/example_configs/3axis_DAC.yaml +++ /dev/null @@ -1,111 +0,0 @@ -name: "ESP32 Dev Controller V4" -board: "ESP32 Dev Controller V4" - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -axes: - shared_stepper_disable: gpio.13:low - - x: - steps_per_mm: 800 - max_rate: 2000 - acceleration: 25 - max_travel: 1000 - 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_all: gpio.17:low:pu - stepstick: - direction: gpio.14 - step: gpio.12 - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate: 2000 - acceleration: 25 - max_travel: 1000 - 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_all: gpio.4:low:pu - stepstick: - direction: gpio.15 - step: gpio.26 - motor1: - null_motor: - - z: - steps_per_mm: 800 - max_rate: 2000 - acceleration: 25 - max_travel: 1000 - steps_per_mm: 800.000 - max_rate: 5000.000 - acceleration: 100.000 - max_travel: 300.000 - soft_limits: false - homing: - cycle: 1 - 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_all: gpio.16:low:pu - stepstick: - direction: gpio.33 - step: gpio.27 - motor1: - null_motor: - -coolant: - flood: NO_PIN - mist: NO_PIN - -comms: - wifi_ap: - ip_address: "192.168.0.1" - ssid: FluidNC - -probe: - pin: gpio.32:low:pu - -DAC: - output_pin: gpio.25 diff --git a/example_configs/3axis_v4.yaml b/example_configs/3axis_v4.yaml index 2e3b4b4fa..b6d7f80b6 100644 --- a/example_configs/3axis_v4.yaml +++ b/example_configs/3axis_v4.yaml @@ -1,16 +1,14 @@ name: "ESP32 Dev Controller V4" board: "ESP32 Dev Controller V4" -yaml_wiki: "https://github.com/bdring/FluidNC/wiki/YAML-Config-File" -idle_time: 250 -step_type: rmt -dir_delay_microseconds: 1 -pulse_microseconds: 2 -disable_delay_us: 0 -homing_init_lock: false +stepping: + engine: RMT + idle_ms: 250 + dir_delay_us: 1 + pulse_us: 2 + disable_delay_us: 0 axes: - number_axis: 3 shared_stepper_disable: gpio.13:low x: @@ -19,6 +17,7 @@ axes: acceleration: 25 max_travel: 1000 homing: + cycle: 2 mpos: 10 positive_direction: false @@ -36,6 +35,7 @@ axes: acceleration: 25 max_travel: 1000 homing: + cycle: 2 mpos: 10 positive_direction: false @@ -53,6 +53,7 @@ axes: acceleration: 25 max_travel: 1000 homing: + cycle: 1 mpos: 10 positive_direction: true @@ -64,27 +65,44 @@ axes: motor1: null_motor: +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + cs: gpio.5 + card_detect: NO_PIN coolant: flood: gpio.25 mist: gpio.21 comms: - wifi_sta: - ssid: Barts-WLAN - - wifi_ap: - ip_address: "192.168.0.1" - ssid: FluidNC + telnet_enable: true + telnet_port: 23 + http_enable: true + http_port: 80 + hostname: fluidnc + wifi_ap: + ssid: FluidNC + ip_address: 10.0.0.1 + gateway: 10.0.0.1 + netmask: 255.255.0.0 + dhcp: true + channel: 1 probe: - pin: gpio.32:low:pu + pin: gpio.32:low:pu -pwm: +PWM: + pwm_freq: 5000 output_pin: gpio.2 enable_pin: gpio.22 - pwm_off: 0.0 - pwm_min: 0.0 - pwm_max: 100.0 - min_rpm: 0 - max_rpm: 1000 + direction_pin: NO_PIN + disable_with_zero_speed: false + zero_speed_with_disable: true + spinup_ms: 0 + spindown_ms: 0 + tool: 0 + speeds: 0=0% 10000=100% diff --git a/example_configs/6_pack_TMC2130.yaml b/example_configs/6_pack_TMC2130.yaml index c25f5b05b..c6ff13d1e 100644 --- a/example_configs/6_pack_TMC2130.yaml +++ b/example_configs/6_pack_TMC2130.yaml @@ -135,11 +135,14 @@ i2so: ws: gpio.17 spi: - cs: gpio.5 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 @@ -196,9 +199,6 @@ user_outputs: digital2: NO_PIN digital3: NO_PIN -sdcard: - card_detect: NO_PIN - software_debounce_ms: 0 laser_mode: false arc_tolerance: 0.002 diff --git a/example_configs/6_pack_TMC5160.yaml b/example_configs/6_pack_TMC5160.yaml index 898cd5e02..bdb9ebfa6 100644 --- a/example_configs/6_pack_TMC5160.yaml +++ b/example_configs/6_pack_TMC5160.yaml @@ -135,11 +135,14 @@ i2so: ws: gpio.17 spi: - cs: gpio.5 miso: gpio.19 mosi: gpio.23 sck: gpio.18 +sdcard: + cs: gpio.5 + card_detect: NO_PIN + control: safety_door: NO_PIN reset: NO_PIN @@ -196,9 +199,6 @@ user_outputs: digital2: NO_PIN digital3: NO_PIN -sdcard: - card_detect: NO_PIN - software_debounce_ms: 0 laser_mode: false arc_tolerance: 0.002 diff --git a/example_configs/TMC2130_pen.yaml b/example_configs/TMC2130_pen.yaml index 0c1162e09..ca7621f6b 100644 --- a/example_configs/TMC2130_pen.yaml +++ b/example_configs/TMC2130_pen.yaml @@ -107,6 +107,15 @@ axes: output_pin: gpio.27 min_pulse_us: 2100 max_pulse_us: 1000 + +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + cs: gpio.5 + card_detect: NO_PIN coolant: flood: NO_PIN diff --git a/example_configs/TMC2209.yaml b/example_configs/TMC2209.yaml index 3b2a1bb73..33dbec4b4 100644 --- a/example_configs/TMC2209.yaml +++ b/example_configs/TMC2209.yaml @@ -114,11 +114,14 @@ a: direction: gpio.15 spi: - cs: gpio.5 miso: gpio.19 mosi: gpio.23 sck: gpio.18 +sdcard: + cs: gpio.5 + card_detect: NO_PIN + control: safety_door: NO_PIN reset: NO_PIN @@ -175,9 +178,6 @@ user_outputs: digital2: NO_PIN digital3: NO_PIN -sdcard: - card_detect: NO_PIN - software_debounce_ms: 0 laser_mode: false arc_tolerance: 0.002 diff --git a/example_configs/dac.yaml b/example_configs/dac.yaml deleted file mode 100644 index a58c5c98d..000000000 --- a/example_configs/dac.yaml +++ /dev/null @@ -1,119 +0,0 @@ -name: "ESP32 Dev Controller V4" -board: "ESP32 Dev Controller V4" - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -axes: - shared_stepper_disable: gpio.13:low - - x: - steps_per_mm: 800 - max_rate: 2000 - acceleration: 25 - max_travel: 1000 - 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_all: gpio.17:low:pu - stepstick: - direction: gpio.14 - step: gpio.12 - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate: 2000 - acceleration: 25 - max_travel: 1000 - 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_all: gpio.4:low:pu - stepstick: - direction: gpio.15 - step: gpio.26 - motor1: - null_motor: - - z: - steps_per_mm: 800 - max_rate: 2000 - acceleration: 25 - max_travel: 1000 - steps_per_mm: 800.000 - max_rate: 5000.000 - acceleration: 100.000 - max_travel: 300.000 - soft_limits: false - homing: - cycle: 1 - 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_all: gpio.16:low:pu - stepstick: - direction: gpio.33 - step: gpio.27 - motor1: - null_motor: - -coolant: - flood: NO_PIN - mist: NO_PIN - -comms: - wifi_ap: - ip_address: "192.168.0.1" - ssid: FluidNC - -probe: - pin: gpio.32:low:pu - -DAC: - output_pin: gpio.25 - enable_pin: NO_PIN - direction_pin: NO_PIN - disable_with_zero_speed: false - zero_speed_with_disable: true - spinup_ms: 0 - spindown_ms: 0 - tool: 100 - speeds: 0=0.000% 10000=100.000% diff --git a/example_configs/test_drive_SD.yaml b/example_configs/test_drive_SD.yaml new file mode 100644 index 000000000..ae020744f --- /dev/null +++ b/example_configs/test_drive_SD.yaml @@ -0,0 +1,98 @@ +board: None +name: Default (Test Drive) +stepping: + engine: RMT + idle_ms: 255 + pulse_us: 4 + dir_delay_us: 0 + disable_delay_us: 0 + +axes: + shared_stepper_disable: NO_PIN + x: + steps_per_mm: 320.000 + max_rate: 1000.000 + acceleration: 25.000 + max_travel: 200.000 + soft_limits: false + + y: + steps_per_mm: 320.000 + max_rate: 1000.000 + acceleration: 25.000 + max_travel: 200.000 + soft_limits: false + + z: + steps_per_mm: 320.000 + max_rate: 1000.000 + acceleration: 25.000 + max_travel: 200.000 + soft_limits: false + +spi: + miso: NO_PIN + mosi: NO_PIN + sck: NO_PIN + +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 + +comms: + +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 + +sdcard: + card_detect: NO_PIN + cs: gpio.5 + +software_debounce_ms: 0 +laser_mode: false +arc_tolerance: 0.002 +junction_deviation: 0.010 +verbose_errors: false +report_inches: false +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_10V.yaml b/example_configs/tmc2209_10V.yaml index 7529a6937..2bfaed7f4 100644 --- a/example_configs/tmc2209_10V.yaml +++ b/example_configs/tmc2209_10V.yaml @@ -141,6 +141,15 @@ axes: motor1: null_motor: + +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + cs: gpio.5 + card_detect: NO_PIN comms: wifi_ap: diff --git a/example_configs/tmc2209_BESC.yaml b/example_configs/tmc2209_BESC.yaml index 4b069bee8..405c9bc20 100644 --- a/example_configs/tmc2209_BESC.yaml +++ b/example_configs/tmc2209_BESC.yaml @@ -141,6 +141,15 @@ axes: motor1: null_motor: + +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + cs: gpio.5 + card_detect: NO_PIN comms: wifi_ap: diff --git a/example_configs/tmc2209_huanyang.yml b/example_configs/tmc2209_huanyang.yml index dd84a7577..8fe49e0c4 100644 --- a/example_configs/tmc2209_huanyang.yml +++ b/example_configs/tmc2209_huanyang.yml @@ -140,6 +140,15 @@ axes: motor1: null_motor: + +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + cs: gpio.5 + card_detect: NO_PIN comms: wifi_ap: diff --git a/example_configs/tmc2209_laser.yaml b/example_configs/tmc2209_laser.yaml index 115e63363..a5b1652b5 100644 --- a/example_configs/tmc2209_laser.yaml +++ b/example_configs/tmc2209_laser.yaml @@ -141,6 +141,15 @@ axes: motor1: null_motor: + +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + card_detect: NO_PIN + cs: gpio.5 comms: wifi_ap: diff --git a/example_configs/tmc2209_relay.yaml b/example_configs/tmc2209_relay.yaml index 7457f1a67..f70e1a772 100644 --- a/example_configs/tmc2209_relay.yaml +++ b/example_configs/tmc2209_relay.yaml @@ -141,6 +141,15 @@ axes: motor1: null_motor: + +spi: + miso: gpio.19 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + cs: gpio.5 + card_detect: NO_PIN comms: wifi_ap: From 55e1a59f7a6a88523448500b001840815262393a Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:34:22 -1000 Subject: [PATCH 15/46] Rename Trinamic Spi driver class, fix SD config message --- ...inamicDriver.cpp => TrinamicSpiDriver.cpp} | 20 +++++++++---------- .../{TrinamicDriver.h => TrinamicSpiDriver.h} | 14 ++++++------- FluidNC/src/SDCard.cpp | 1 + 3 files changed, 18 insertions(+), 17 deletions(-) rename FluidNC/src/Motors/{TrinamicDriver.cpp => TrinamicSpiDriver.cpp} (95%) rename FluidNC/src/Motors/{TrinamicDriver.h => TrinamicSpiDriver.h} (84%) diff --git a/FluidNC/src/Motors/TrinamicDriver.cpp b/FluidNC/src/Motors/TrinamicSpiDriver.cpp similarity index 95% rename from FluidNC/src/Motors/TrinamicDriver.cpp rename to FluidNC/src/Motors/TrinamicSpiDriver.cpp index f220c41c7..ad2cb8116 100644 --- a/FluidNC/src/Motors/TrinamicDriver.cpp +++ b/FluidNC/src/Motors/TrinamicSpiDriver.cpp @@ -5,7 +5,7 @@ This is used for Trinamic SPI controlled stepper motor drivers. */ -#include "TrinamicDriver.h" +#include "TrinamicSpiDriver.h" #include "../Machine/MachineConfig.h" @@ -13,12 +13,12 @@ #include namespace MotorDrivers { - TrinamicDriver::TrinamicDriver(uint16_t driver_part_number, int8_t spi_index) : + TrinamicSpiDriver::TrinamicSpiDriver(uint16_t driver_part_number, int8_t spi_index) : TrinamicBase(driver_part_number), _spi_index(spi_index) {} uint8_t daisy_chain_cs = -1; - void TrinamicDriver::init() { + void TrinamicSpiDriver::init() { _has_errors = false; auto spiConfig = config->_spi; @@ -97,12 +97,12 @@ namespace MotorDrivers { /* This is the startup message showing the basic definition */ - void TrinamicDriver::config_message() { + void TrinamicSpiDriver::config_message() { log_info(" Trinamic TMC" << _driver_part_number << " Step:" << _step_pin.name() << " Dir:" << _dir_pin.name() << " CS:" << _cs_pin.name() << " Disable:" << _disable_pin.name() << " Index:" << _spi_index << " R:" << _r_sense); } - bool TrinamicDriver::test() { + bool TrinamicSpiDriver::test() { if (_has_errors) { return false; } @@ -152,7 +152,7 @@ namespace MotorDrivers { uint16_t run (mA) float hold (as a percentage of run) */ - void TrinamicDriver::read_settings() { + void TrinamicSpiDriver::read_settings() { if (_has_errors) { return; } @@ -173,7 +173,7 @@ namespace MotorDrivers { tmcstepper->rms_current(run_i_ma, hold_i_percent); } - bool TrinamicDriver::set_homing_mode(bool isHoming) { + bool TrinamicSpiDriver::set_homing_mode(bool isHoming) { set_mode(isHoming); return true; } @@ -183,7 +183,7 @@ namespace MotorDrivers { Many people will want quiet and stallguard homing. Stallguard only run in Coolstep mode, so it will need to switch to Coolstep when homing */ - void TrinamicDriver::set_mode(bool isHoming) { + void TrinamicSpiDriver::set_mode(bool isHoming) { if (_has_errors) { return; } @@ -232,7 +232,7 @@ namespace MotorDrivers { /* This is the stallguard tuning info. It is call debug, so it could be generic across all classes. */ - void TrinamicDriver::debug_message() { + void TrinamicSpiDriver::debug_message() { if (_has_errors) { return; } @@ -263,7 +263,7 @@ namespace MotorDrivers { // this can use the enable feature over SPI. The dedicated pin must be in the enable mode, // but that can be hardwired that way. - void IRAM_ATTR TrinamicDriver::set_disable(bool disable) { + void IRAM_ATTR TrinamicSpiDriver::set_disable(bool disable) { if (_has_errors) { return; } diff --git a/FluidNC/src/Motors/TrinamicDriver.h b/FluidNC/src/Motors/TrinamicSpiDriver.h similarity index 84% rename from FluidNC/src/Motors/TrinamicDriver.h rename to FluidNC/src/Motors/TrinamicSpiDriver.h index 5125a97ad..ee77bfc32 100644 --- a/FluidNC/src/Motors/TrinamicDriver.h +++ b/FluidNC/src/Motors/TrinamicSpiDriver.h @@ -19,7 +19,7 @@ class TMC2130Stepper; // Forward declaration namespace MotorDrivers { - class TrinamicDriver : public TrinamicBase { + class TrinamicSpiDriver : public TrinamicBase { private: const int _spi_freq = 100000; @@ -39,9 +39,9 @@ namespace MotorDrivers { void config_message() override; public: - TrinamicDriver(uint16_t driver_part_number) : TrinamicDriver(driver_part_number, -1) {} + TrinamicSpiDriver(uint16_t driver_part_number) : TrinamicSpiDriver(driver_part_number, -1) {} - TrinamicDriver(uint16_t driver_part_number, int8_t spi_index); + TrinamicSpiDriver(uint16_t driver_part_number, int8_t spi_index); // Overrides for inherited methods void init() override; @@ -67,17 +67,17 @@ namespace MotorDrivers { const char* name() const override { return "trinamic_spi"; } }; - class TMC2130 : public TrinamicDriver { + class TMC2130 : public TrinamicSpiDriver { public: - TMC2130() : TrinamicDriver(2130) {} + TMC2130() : TrinamicSpiDriver(2130) {} // Name of the configurable. Must match the name registered in the cpp file. const char* name() const override { return "tmc_2130"; } }; - class TMC5160 : public TrinamicDriver { + class TMC5160 : public TrinamicSpiDriver { public: - TMC5160() : TrinamicDriver(5160) {} + TMC5160() : TrinamicSpiDriver(5160) {} // Name of the configurable. Must match the name registered in the cpp file. const char* name() const override { return "tmc_5160"; } diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index 2631650d5..7fcb9a995 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -195,6 +195,7 @@ void SDCard::init() { _cardDetect.report("SD Card Detect"); init_message = false; } + log_info("SD Card cs:" << _cs.name() << " dectect:" << _cardDetect.name()); } _cs.setAttr(Pin::Attr::Output); From 21db8167ac2c1d44887f8b3721988cb7a172891b Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:34:41 -1000 Subject: [PATCH 16/46] Fixed SD config message so it only shows when a cs is defined --- FluidNC/src/SDCard.cpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/FluidNC/src/SDCard.cpp b/FluidNC/src/SDCard.cpp index 7fcb9a995..c3415e9e3 100644 --- a/FluidNC/src/SDCard.cpp +++ b/FluidNC/src/SDCard.cpp @@ -188,14 +188,16 @@ const char* SDCard::filename() { void SDCard::init() { static bool init_message = true; // used to show messages only once. - if (!config->_spi->defined()) { - log_error("SD needs SPI defined"); - } else { - if (init_message) { - _cardDetect.report("SD Card Detect"); - init_message = false; + if (_cs.defined()) { + if (!config->_spi->defined()) { + log_error("SD needs SPI defined"); + } else { + if (init_message) { + _cardDetect.report("SD Card Detect"); + init_message = false; + } + log_info("SD Card cs:" << _cs.name() << " dectect:" << _cardDetect.name()); } - log_info("SD Card cs:" << _cs.name() << " dectect:" << _cardDetect.name()); } _cs.setAttr(Pin::Attr::Output); From 765d900b6ddfdfd2a0125369a3980fd02bd4bf61 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:35:06 -1000 Subject: [PATCH 17/46] Control pin initial state checks --- FluidNC/src/ControlPin.cpp | 10 +++++++++- FluidNC/src/Protocol.cpp | 3 ++- FluidNC/src/Protocol.h | 3 ++- 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/FluidNC/src/ControlPin.cpp b/FluidNC/src/ControlPin.cpp index 0dc303c9a..994d48a73 100644 --- a/FluidNC/src/ControlPin.cpp +++ b/FluidNC/src/ControlPin.cpp @@ -8,7 +8,9 @@ void IRAM_ATTR ControlPin::handleISR() { bool pinState = _pin.read(); _value = pinState; - _rtVariable = pinState; + if (pinState) { + _rtVariable = pinState; + } } void ControlPin::init() { @@ -22,6 +24,12 @@ void ControlPin::init() { } _pin.setAttr(attr); _pin.attachInterrupt(this, CHANGE); + _rtVariable = false; + _value = _pin.read(); + // Control pins must start in inactive state + if (_value) { + rtAlarm = ExecAlarm::ControlPin; + } } void ControlPin::report(char* status) { diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 415ea56ae..5f6391344 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -34,6 +34,7 @@ std::map AlarmNames = { { ExecAlarm::HomingFailPulloff, "Homing Fail Pulloff" }, { ExecAlarm::HomingFailApproach, "Homing Fail Approach" }, { ExecAlarm::SpindleControl, "Spindle Control" }, + { ExecAlarm::ControlPin, "Control Pin Initially On" }, }; volatile Accessory rtAccessoryOverride; // Global realtime executor bitflag variable for spindle/coolant overrides. @@ -699,7 +700,7 @@ void protocol_exec_rt_system() { protocol_do_macro(1); } if (rtButtonMacro2) { - rtButtonMacro0 = false; + rtButtonMacro2 = false; protocol_do_macro(2); } if (rtButtonMacro3) { diff --git a/FluidNC/src/Protocol.h b/FluidNC/src/Protocol.h index 6db271293..5809b3516 100644 --- a/FluidNC/src/Protocol.h +++ b/FluidNC/src/Protocol.h @@ -90,9 +90,10 @@ enum class ExecAlarm : uint8_t { HomingFailPulloff = 8, HomingFailApproach = 9, SpindleControl = 10, + ControlPin = 11, }; -extern volatile ExecAlarm rtAlarm; // Global realtime executor bitflag variable for setting various alarms. +extern volatile ExecAlarm rtAlarm; // Global realtime executor variable for setting various alarms. #include extern std::map AlarmNames; From 0bbff0c9d88567a1a266bd2da69866cacd0c4277 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:35:20 -1000 Subject: [PATCH 18/46] Better message and propagate rtAlarm through protocol_reset() --- FluidNC/src/ControlPin.cpp | 1 + FluidNC/src/Protocol.cpp | 4 +++- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/FluidNC/src/ControlPin.cpp b/FluidNC/src/ControlPin.cpp index 994d48a73..10ce01b95 100644 --- a/FluidNC/src/ControlPin.cpp +++ b/FluidNC/src/ControlPin.cpp @@ -28,6 +28,7 @@ void ControlPin::init() { _value = _pin.read(); // Control pins must start in inactive state if (_value) { + log_error(_legend << " pin is active at startup"); rtAlarm = ExecAlarm::ControlPin; } } diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 5f6391344..2d4c330c4 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -96,11 +96,13 @@ void protocol_reset() { rtSleep = false; rtCycleStop = false; rtAccessoryOverride.value = 0; - rtAlarm = ExecAlarm::None; rtFOverride = FeedOverride::Default; rtROverride = RapidOverride::Default; rtSOverride = SpindleSpeedOverride::Default; spindle_stop_ovr.value = 0; + + // Do not clear rtAlarm because it might have been set during configuration + // rtAlarm = ExecAlarm::None; } static int32_t idleEndTime = 0; From 9bacba554f2a0eead97408b86f77b768db77abe3 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:35:33 -1000 Subject: [PATCH 19/46] More reporting improvements --- FluidNC/src/Control.cpp | 17 ++++++++--------- FluidNC/src/Control.h | 5 +++-- FluidNC/src/ControlPin.cpp | 6 ++---- FluidNC/src/ControlPin.h | 2 +- FluidNC/src/Error.cpp | 1 + FluidNC/src/Error.h | 1 + FluidNC/src/ProcessSettings.cpp | 28 +++++++++++++++++++++------- FluidNC/src/Report.cpp | 7 +------ 8 files changed, 38 insertions(+), 29 deletions(-) diff --git a/FluidNC/src/Control.cpp b/FluidNC/src/Control.cpp index 4d62e452f..630c5a7ac 100644 --- a/FluidNC/src/Control.cpp +++ b/FluidNC/src/Control.cpp @@ -32,15 +32,14 @@ void Control::group(Configuration::HandlerBase& handler) { handler.item("macro3", _macro3._pin); } -void Control::report(char* status) { - _safetyDoor.report(status); - _reset.report(status); - _feedHold.report(status); - _cycleStart.report(status); - _macro0.report(status); - _macro1.report(status); - _macro2.report(status); - _macro3.report(status); +String Control::report() { + return _safetyDoor.report() + _safetyDoor.report() + _reset.report() + _feedHold.report() + _cycleStart.report() + _macro0.report() + + _macro1.report() + _macro2.report() + _macro3.report(); +} + +bool Control::stuck() { + return _safetyDoor.get() || _reset.get() || _feedHold.get() || _cycleStart.get() || _macro0.get() || _macro1.get() || _macro2.get() || + _macro3.get(); } // Returns if safety door is ajar(T) or closed(F), based on pin state. diff --git a/FluidNC/src/Control.h b/FluidNC/src/Control.h index e07ddbd6d..9dc523ae1 100644 --- a/FluidNC/src/Control.h +++ b/FluidNC/src/Control.h @@ -28,8 +28,9 @@ class Control : public Configuration::Configurable { // Configuration handlers. void group(Configuration::HandlerBase& handler) override; - bool system_check_safety_door_ajar(); - void report(char* status); + bool stuck(); + bool system_check_safety_door_ajar(); + String report(); ~Control() = default; }; diff --git a/FluidNC/src/ControlPin.cpp b/FluidNC/src/ControlPin.cpp index 10ce01b95..42bee654c 100644 --- a/FluidNC/src/ControlPin.cpp +++ b/FluidNC/src/ControlPin.cpp @@ -33,10 +33,8 @@ void ControlPin::init() { } } -void ControlPin::report(char* status) { - if (get()) { - addPinReport(status, _letter); - } +String ControlPin::report() { + return get() ? String(_letter) : String(""); } ControlPin::~ControlPin() { diff --git a/FluidNC/src/ControlPin.h b/FluidNC/src/ControlPin.h index 1a0c47fc8..360047a08 100644 --- a/FluidNC/src/ControlPin.h +++ b/FluidNC/src/ControlPin.h @@ -22,7 +22,7 @@ class ControlPin { void init(); bool get() { return _value; } - void report(char* status); + String report(); ~ControlPin(); }; diff --git a/FluidNC/src/Error.cpp b/FluidNC/src/Error.cpp index 140abf162..ca35d46ce 100644 --- a/FluidNC/src/Error.cpp +++ b/FluidNC/src/Error.cpp @@ -45,6 +45,7 @@ std::map ErrorNames = { { Error::GcodeG43DynamicAxisError, "Gcode G43 dynamic axis error" }, { Error::GcodeMaxValueExceeded, "Gcode max value exceeded" }, { Error::PParamMaxExceeded, "P param max exceeded" }, + { Error::CheckControlPins, "Check control pins" }, { Error::FsFailedMount, "Failed to mount device" }, { Error::FsFailedRead, "Read failed" }, { Error::FsFailedOpenDir, "Failed to open directory" }, diff --git a/FluidNC/src/Error.h b/FluidNC/src/Error.h index b67d0ff40..f0ac285fd 100644 --- a/FluidNC/src/Error.h +++ b/FluidNC/src/Error.h @@ -49,6 +49,7 @@ enum class Error : uint8_t { GcodeG43DynamicAxisError = 37, GcodeMaxValueExceeded = 38, PParamMaxExceeded = 39, + CheckControlPins = 40, FsFailedMount = 60, // SD Failed to mount FsFailedRead = 61, // SD Failed to read file FsFailedOpenDir = 62, // SD card failed to open directory diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index ceed8f22f..5bbeadc5b 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -192,13 +192,27 @@ static Error toggle_check_mode(const char* value, WebUI::AuthenticationLevel aut } return Error::Ok; } +static Error isStuck() { + // Block if a control pin is stuck on + if (config->_control->system_check_safety_door_ajar()) { + rtAlarm = ExecAlarm::ControlPin; + return Error::CheckDoor; + } + if (config->_control->stuck()) { + log_info("Control pins:" << config->_control->report()); + rtAlarm = ExecAlarm::ControlPin; + return Error::CheckControlPins; + } + return Error::Ok; +} static Error disable_alarm_lock(const char* value, WebUI::AuthenticationLevel auth_level, Print& out) { if (sys.state == State::ConfigAlarm) { return Error::ConfigurationInvalid; - } else if (sys.state == State::Alarm) { - // Block if safety door is ajar. - if (config->_control->system_check_safety_door_ajar()) { - return Error::CheckDoor; + } + if (sys.state == State::Alarm) { + Error err = isStuck(); + if (err != Error::Ok) { + return err; } report_feedback_message(Message::AlarmUnlock); sys.state = State::Idle; @@ -214,12 +228,12 @@ static Error home(int cycle) { if (sys.state == State::ConfigAlarm) { return Error::ConfigurationInvalid; } - if (!Machine::Axes::homingMask) { return Error::SettingDisabled; } - if (config->_control->system_check_safety_door_ajar()) { - return Error::CheckDoor; // Block if safety door is ajar. + Error err = isStuck(); + if (err != Error::Ok) { + return err; } sys.state = State::Homing; // Set system state variable diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index a8540a823..650317b93 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -545,12 +545,7 @@ String pinString() { } } - // XXX WMB change _control->report() to return a String - char status[20]; - status[0] = '\0'; - config->_control->report(status); - - pins += status; + pins += config->_control->report(); return pins; } From 275df1390e1e8c97d3be703f27bc7f3e5df54684 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 21 Sep 2021 19:35:47 -1000 Subject: [PATCH 20/46] Fixed $G Report --- FluidNC/src/Report.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index 650317b93..78c6eb17d 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -290,7 +290,7 @@ void report_gcode_modes(Print& client) { } client << mode; - client << 'G' << (gc_state.modal.coord_select + 54); + client << " G" << (gc_state.modal.coord_select + 54); switch (gc_state.modal.plane_select) { case Plane::XY: @@ -396,11 +396,11 @@ void report_gcode_modes(Print& client) { client << " M56"; } - client << " T " << gc_state.tool; + client << " T" << gc_state.tool; // XXX WMB format according to config->_reportInches ? %.1f : %.0f client << " F" << gc_state.feed_rate; - client << " # " << uint32_t(gc_state.spindle_speed); - client << '\n'; + client << " S" << uint32_t(gc_state.spindle_speed); + client << "]\n"; } // Prints build info line From 92dce2f4d037e8c33b2d4b8f3b5af1117cf15ec4 Mon Sep 17 00:00:00 2001 From: bdring Date: Fri, 24 Sep 2021 20:50:14 -0500 Subject: [PATCH 21/46] Update HOWTO-INSTALL.txt --- install_scripts/HOWTO-INSTALL.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/install_scripts/HOWTO-INSTALL.txt b/install_scripts/HOWTO-INSTALL.txt index fd9bfbd34..42159d737 100644 --- a/install_scripts/HOWTO-INSTALL.txt +++ b/install_scripts/HOWTO-INSTALL.txt @@ -1,4 +1,4 @@ -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 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) From 3113bc713732ba8f47b2766ba06255c542bafde0 Mon Sep 17 00:00:00 2001 From: bdring Date: Sat, 25 Sep 2021 16:28:05 -0500 Subject: [PATCH 22/46] WIP - Cleanup messages --- FluidNC/data/6_pack_external_huanyang.yaml | 176 +++++++++++++++++++++ FluidNC/src/Spindles/HuanyangSpindle.cpp | 6 +- FluidNC/src/Spindles/VFDSpindle.cpp | 16 +- 3 files changed, 188 insertions(+), 10 deletions(-) create mode 100644 FluidNC/data/6_pack_external_huanyang.yaml diff --git a/FluidNC/data/6_pack_external_huanyang.yaml b/FluidNC/data/6_pack_external_huanyang.yaml new file mode 100644 index 000000000..9cbdd391a --- /dev/null +++ b/FluidNC/data/6_pack_external_huanyang.yaml @@ -0,0 +1,176 @@ +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 + spinup_ms: 10 + spindown_ms: 10 + modbus_id: 1 + spinup_ms: 0 + spindown_ms: 0 + tool: 0 + speeds: speeds: 0=0% 0=25% 6000=25% 24000=100% + diff --git a/FluidNC/src/Spindles/HuanyangSpindle.cpp b/FluidNC/src/Spindles/HuanyangSpindle.cpp index 92f21d908..8664a6e28 100644 --- a/FluidNC/src/Spindles/HuanyangSpindle.cpp +++ b/FluidNC/src/Spindles/HuanyangSpindle.cpp @@ -222,8 +222,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 +240,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/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index b7b17a132..22fd9ab41 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -57,20 +57,20 @@ namespace Spindles { 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); - hex_msg(rx_message, "RS485 Rx: ", read_length); + //hex_msg(cmd.msg, "RS485 Tx: ", cmd.tx_length); + //hex_msg(rx_message, "RS485 Rx: ", read_length); #endif } void VFD::reportCmdErrors(ModbusCommand cmd, uint8_t* rx_message, size_t read_length, uint8_t id) { #ifdef DEBUG_VFD - hex_msg(cmd.msg, "RS485 Tx: ", cmd.tx_length); - hex_msg(rx_message, "RS485 Rx: ", read_length); + //hex_msg(cmd.msg, "RS485 Tx: ", cmd.tx_length); + //hex_msg(rx_message, "RS485 Rx: ", read_length); if (read_length != 0) { 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"); } @@ -333,7 +333,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 @@ -365,7 +365,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 +379,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) { From 0c18659f0e31720a84212befe09f9a5c3b2eee37 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sat, 25 Sep 2021 14:20:20 -1000 Subject: [PATCH 23/46] Fix WebUI access to NVS Settings and reordered the NVS settings so the most likely ones to change are at the top. --- FluidNC/src/Configuration/JsonGenerator.cpp | 14 ++-- FluidNC/src/ProcessSettings.cpp | 2 +- FluidNC/src/Settings.cpp | 8 +-- FluidNC/src/WebUI/JSONEncoder.cpp | 13 ++-- FluidNC/src/WebUI/WebSettings.cpp | 80 +++++++++++---------- 5 files changed, 64 insertions(+), 53 deletions(-) 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/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index 5bbeadc5b..b0cd04998 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -554,7 +554,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/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/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..32522c209 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -641,8 +641,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(); @@ -1022,20 +1031,48 @@ 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); + + 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 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, @@ -1079,37 +1116,8 @@ 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); - - 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 - + 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); #endif } From 3c3ca170db97300afbdd3f5cde633556de0b97c5 Mon Sep 17 00:00:00 2001 From: bdring Date: Sun, 26 Sep 2021 10:25:44 -0500 Subject: [PATCH 24/46] Fixed reset during running spindle - moved hex_msg to Report.cpp - clarified some messages --- FluidNC/src/Report.cpp | 12 +++++++ FluidNC/src/Report.h | 2 ++ FluidNC/src/Spindles/HuanyangSpindle.cpp | 1 + FluidNC/src/Spindles/VFDSpindle.cpp | 34 ++++++------------- FluidNC/src/Spindles/VFDSpindle.h | 3 -- FluidNC/src/Spindles/YL620Spindle.cpp | 2 +- .../6_pack_external_huanyang.yaml | 3 +- install_scripts/HOWTO-INSTALL.txt | 3 +- 8 files changed, 29 insertions(+), 31 deletions(-) rename {FluidNC/data => example_configs}/6_pack_external_huanyang.yaml (98%) diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index 8cda30719..e23cd4115 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -672,6 +672,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..ab3c8aa09 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; diff --git a/FluidNC/src/Spindles/HuanyangSpindle.cpp b/FluidNC/src/Spindles/HuanyangSpindle.cpp index 8664a6e28..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; diff --git a/FluidNC/src/Spindles/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index 22fd9ab41..71298a28d 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,33 +39,16 @@ 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); - //hex_msg(rx_message, "RS485 Rx: ", read_length); + hex_msg(cmd.msg, "RS485 Tx: ", cmd.tx_length); + hex_msg(rx_message, "RS485 Rx: ", read_length); #endif } void VFD::reportCmdErrors(ModbusCommand cmd, uint8_t* rx_message, size_t read_length, uint8_t id) { #ifdef DEBUG_VFD - //hex_msg(cmd.msg, "RS485 Tx: ", cmd.tx_length); - //hex_msg(rx_message, "RS485 Rx: ", read_length); + hex_msg(cmd.msg, "RS485 Tx: ", cmd.tx_length); + hex_msg(rx_message, "RS485 Rx: ", read_length); if (read_length != 0) { if (rx_message[0] != id) { @@ -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,6 +292,8 @@ namespace Spindles { } config_message(); + + set_mode(SpindleState::Disable, true); } // Checks for all the required pin definitions @@ -409,6 +396,7 @@ namespace Spindles { _current_state = mode; return true; } + void VFD::set_mode(SpindleState mode, bool critical) { if (vfd_cmd_queue) { VFDaction action; @@ -449,7 +437,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..c76b03fb3 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 { 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/data/6_pack_external_huanyang.yaml b/example_configs/6_pack_external_huanyang.yaml similarity index 98% rename from FluidNC/data/6_pack_external_huanyang.yaml rename to example_configs/6_pack_external_huanyang.yaml index 9cbdd391a..aadaea050 100644 --- a/FluidNC/data/6_pack_external_huanyang.yaml +++ b/example_configs/6_pack_external_huanyang.yaml @@ -172,5 +172,4 @@ Huanyang: spinup_ms: 0 spindown_ms: 0 tool: 0 - speeds: speeds: 0=0% 0=25% 6000=25% 24000=100% - + speeds: 0=0% 0=25% 6000=25% 24000=100% diff --git a/install_scripts/HOWTO-INSTALL.txt b/install_scripts/HOWTO-INSTALL.txt index 42159d737..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 - 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) - - From 3754b7bf87cc0339c32a22e5b30efd93663a1dc0 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 26 Sep 2021 09:46:25 -1000 Subject: [PATCH 25/46] Eliminate limits_two_switches_on_axis which is no longer needed --- FluidNC/src/Limits.cpp | 4 ++++ FluidNC/src/Limits.h | 6 ++++++ FluidNC/src/Machine/MachineConfig.cpp | 1 - FluidNC/src/Machine/MachineConfig.h | 8 -------- FluidNC/src/MotionControl.cpp | 8 ++++---- FluidNC/src/Report.cpp | 3 --- example_configs/6_pack_TMC2130.yaml | 1 - example_configs/6_pack_TMC5160.yaml | 1 - example_configs/TMC2209.yaml | 1 - example_configs/test_drive_SD.yaml | 1 - 10 files changed, 14 insertions(+), 20 deletions(-) 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/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index ef610a5ee..255cf4abf 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -54,7 +54,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..778d354ce 100644 --- a/FluidNC/src/Machine/MachineConfig.h +++ b/FluidNC/src/Machine/MachineConfig.h @@ -62,14 +62,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/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/Report.cpp b/FluidNC/src/Report.cpp index 8cda30719..a00f33369 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"; } 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/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: From af1d36934b21a93467a438d046ade34e25b7b43f Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 26 Sep 2021 10:22:54 -1000 Subject: [PATCH 26/46] STA>AP, eliminated wifi/enable, add wifi/mode=None --- FluidNC/src/WebUI/WebSettings.cpp | 9 ++++--- FluidNC/src/WebUI/WebSettings.h | 3 +-- FluidNC/src/WebUI/WifiConfig.cpp | 39 +++++++++++++++++-------------- 3 files changed, 27 insertions(+), 24 deletions(-) diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 4109f4ad4..1a792aa31 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -44,14 +44,14 @@ namespace WebUI { EnumSetting* wifi_radio_mode; enum_opt_t wifiModeOptions = { + { "Off", ESP_WIFI_OFF }, { "STA", ESP_WIFI_STA }, { "AP", ESP_WIFI_AP }, - { "STA_AP", ESP_WIFI_STA_AP }, + { "STA>AP", ESP_WIFI_STA_AP }, }; #endif #ifdef ENABLE_WIFI - EnumSetting* wifi_enable; EnumSetting* wifi_mode; StringSetting* wifi_sta_ssid; @@ -1022,8 +1022,7 @@ 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); + wifi_mode = new EnumSetting("WiFi mode", WEBSET, WA, "ESP116", "WiFi/Mode", WIFI_AP, &wifiModeOptions, NULL); telnet_port = new IntSetting( "Telnet Port", WEBSET, WA, "ESP131", "Telnet/Port", DEFAULT_TELNETSERVER_PORT, MIN_TELNET_PORT, MAX_TELNET_PORT, NULL); @@ -1109,7 +1108,7 @@ namespace WebUI { 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..a86b96e0a 100644 --- a/FluidNC/src/WebUI/WebSettings.h +++ b/FluidNC/src/WebUI/WebSettings.h @@ -8,11 +8,11 @@ #include "../Settings.h" //Radio Mode +const int ESP_WIFI_OFF = 0; 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 - namespace WebUI { #ifdef ENABLE_AUTHENTICATION extern StringSetting* user_password; @@ -21,7 +21,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..6f2e688ee 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -379,23 +379,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 ESP_WIFI_OFF: + log_info("WiFi is disabled"); + return false; + case ESP_WIFI_STA: + if (StartSTA()) { + goto wifi_on; + } + goto wifi_off; + case ESP_WIFI_STA_AP: + if (StartSTA()) { + goto wifi_on; + } + // fall through to fallback to AP mode + case ESP_WIFI_AP: + if (StartAP()) { + goto wifi_on; + } + goto wifi_off; + } + + wifi_off: log_info("WiFi off"); WiFi.mode(WIFI_OFF); return false; From 19304cbc8be4dec18abb5a76f43ac7ca3f41d0e9 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 26 Sep 2021 10:48:13 -1000 Subject: [PATCH 27/46] Use an enum for the values, null default STA SSID --- FluidNC/src/WebUI/WebSettings.cpp | 16 +++++----------- FluidNC/src/WebUI/WebSettings.h | 11 ++++++----- FluidNC/src/WebUI/WifiConfig.cpp | 19 ++++++++++--------- FluidNC/src/WebUI/WifiConfig.h | 6 +++--- 4 files changed, 24 insertions(+), 28 deletions(-) diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 1a792aa31..feba15852 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 = { - { "Off", ESP_WIFI_OFF }, - { "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_mode; StringSetting* wifi_sta_ssid; @@ -1021,8 +1016,7 @@ 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_mode = new EnumSetting("WiFi mode", WEBSET, WA, "ESP116", "WiFi/Mode", WiFiFallback, &wifiModeOptions, NULL); telnet_port = new IntSetting( "Telnet Port", WEBSET, WA, "ESP131", "Telnet/Port", DEFAULT_TELNETSERVER_PORT, MIN_TELNET_PORT, MAX_TELNET_PORT, NULL); diff --git a/FluidNC/src/WebUI/WebSettings.h b/FluidNC/src/WebUI/WebSettings.h index a86b96e0a..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_OFF = 0; -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 diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index 6f2e688ee..80c0e1c6e 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -267,15 +267,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(); @@ -380,20 +381,20 @@ namespace WebUI { wifi_services.end(); switch (wifi_mode->get()) { - case ESP_WIFI_OFF: + case WiFiOff: log_info("WiFi is disabled"); return false; - case ESP_WIFI_STA: + case WiFiSTA: if (StartSTA()) { goto wifi_on; } goto wifi_off; - case ESP_WIFI_STA_AP: + case WiFiFallback: if (StartSTA()) { goto wifi_on; } // fall through to fallback to AP mode - case ESP_WIFI_AP: + case WiFiAP: if (StartAP()) { goto wifi_on; } 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 From cabe88be6296e577b7fd8d1ce406c5cc1422e549 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 26 Sep 2021 11:28:05 -1000 Subject: [PATCH 28/46] Eliminate laser_mode config item. Use Laser spindle instead $32 is supported, but setting it does not do anything. --- FluidNC/src/GCode.cpp | 4 ++-- FluidNC/src/Machine/MachineConfig.cpp | 1 - FluidNC/src/Machine/MachineConfig.h | 1 - FluidNC/src/ProcessSettings.cpp | 9 +++++++++ FluidNC/src/Protocol.cpp | 13 ++++++++----- FluidNC/src/Spindles/Laser.cpp | 2 +- FluidNC/src/Spindles/VFDSpindle.cpp | 11 +---------- FluidNC/src/Stepper.cpp | 2 +- 8 files changed, 22 insertions(+), 21 deletions(-) diff --git a/FluidNC/src/GCode.cpp b/FluidNC/src/GCode.cpp index 64c516873..2497a9a2a 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,7 +1323,7 @@ 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; diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index ef610a5ee..56e78db26 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); diff --git a/FluidNC/src/Machine/MachineConfig.h b/FluidNC/src/Machine/MachineConfig.h index 00da02af7..eb59090cb 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; diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index 5bbeadc5b..ee610b8f1 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 - diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 2d4c330c4..605013b13 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 (config->_disableLaserDuringHold && 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/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/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index b7b17a132..18a7fc8b1 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -312,16 +312,7 @@ namespace Spindles { // 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 "); } 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; From 205b30378e87e0eadbc2a6748864512b35b4af9c Mon Sep 17 00:00:00 2001 From: bdring Date: Mon, 27 Sep 2021 13:24:15 -0500 Subject: [PATCH 29/46] WIP - Removing delays from config files on spindles that don't need them. - Some spindles are closed loop and wait to reach speed - laser does not use delays. --- FluidNC/src/Spindles/H2ASpindle.h | 2 +- FluidNC/src/Spindles/HuanyangSpindle.h | 2 +- FluidNC/src/Spindles/Spindle.h | 8 ++++++-- FluidNC/src/Spindles/VFDSpindle.cpp | 2 +- FluidNC/src/Spindles/VFDSpindle.h | 2 +- FluidNC/src/Spindles/YL620Spindle.h | 2 +- example_configs/6_pack_external_huanyang.yaml | 2 -- example_configs/tmc2209_laser.yaml | 2 -- 8 files changed, 11 insertions(+), 11 deletions(-) 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.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/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 71298a28d..dac7a68b2 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -334,7 +334,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 diff --git a/FluidNC/src/Spindles/VFDSpindle.h b/FluidNC/src/Spindles/VFDSpindle.h index c76b03fb3..a2c62e7af 100644 --- a/FluidNC/src/Spindles/VFDSpindle.h +++ b/FluidNC/src/Spindles/VFDSpindle.h @@ -64,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.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/example_configs/6_pack_external_huanyang.yaml b/example_configs/6_pack_external_huanyang.yaml index aadaea050..56f2bfba4 100644 --- a/example_configs/6_pack_external_huanyang.yaml +++ b/example_configs/6_pack_external_huanyang.yaml @@ -166,8 +166,6 @@ Huanyang: rts_pin: gpio.4 baud: 9600 mode: 8N1 - spinup_ms: 10 - spindown_ms: 10 modbus_id: 1 spinup_ms: 0 spindown_ms: 0 diff --git a/example_configs/tmc2209_laser.yaml b/example_configs/tmc2209_laser.yaml index 336e7b5cc..901141190 100644 --- a/example_configs/tmc2209_laser.yaml +++ b/example_configs/tmc2209_laser.yaml @@ -161,8 +161,6 @@ Laser: direction_pin: NO_PIN 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 From 143299ced1ab9d74668473be6fbc2ff418b998d6 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Mon, 27 Sep 2021 10:15:52 -1000 Subject: [PATCH 30/46] Eliminated redundant disable_laser_during_hold --- FluidNC/src/Machine/MachineConfig.cpp | 1 - FluidNC/src/Machine/MachineConfig.h | 6 ------ FluidNC/src/Protocol.cpp | 2 +- 3 files changed, 1 insertion(+), 8 deletions(-) diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index 56e78db26..c19af14c9 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -54,7 +54,6 @@ namespace Machine { 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); Spindles::SpindleFactory::factory(handler, _spindles); diff --git a/FluidNC/src/Machine/MachineConfig.h b/FluidNC/src/Machine/MachineConfig.h index eb59090cb..cb56e298c 100644 --- a/FluidNC/src/Machine/MachineConfig.h +++ b/FluidNC/src/Machine/MachineConfig.h @@ -69,12 +69,6 @@ namespace Machine { // 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 - // to ensure the laser doesn't inadvertently remain powered while at a stop and cause a fire. - bool _disableLaserDuringHold = true; - // Tracks and reports gcode line numbers. Disabled by default. bool _useLineNumbers = false; diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 605013b13..fa61e4a5f 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -769,7 +769,7 @@ static void protocol_exec_rt_suspend() { restore_spindle = block->spindle; restore_spindle_speed = block->spindle_speed; } - if (config->_disableLaserDuringHold && spindle->isRateAdjusted()) { + if (spindle->isRateAdjusted()) { rtAccessoryOverride.bit.spindleOvrStop = true; } From eca0479aaccf9a08a9e0092934a6f941e3db281f Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 28 Sep 2021 08:21:15 -1000 Subject: [PATCH 31/46] no direction_pin on Laser --- FluidNC/src/Spindles/Laser.h | 6 +++++- FluidNC/src/Spindles/OnOffSpindle.h | 20 +++++++++++++++----- 2 files changed, 20 insertions(+), 6 deletions(-) diff --git a/FluidNC/src/Spindles/Laser.h b/FluidNC/src/Spindles/Laser.h index 6734d9e34..954c432ce 100644 --- a/FluidNC/src/Spindles/Laser.h +++ b/FluidNC/src/Spindles/Laser.h @@ -30,7 +30,11 @@ namespace Spindles { // 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 { + 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..b32fdded1 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,12 +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); - + groupCommon(handler); Spindle::group(handler); } From 32441afbacd43469b52b83f2a590112ebff4321c Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 28 Sep 2021 08:24:31 -1000 Subject: [PATCH 32/46] Oops called Spindle::group() twice --- FluidNC/src/Spindles/OnOffSpindle.h | 1 - 1 file changed, 1 deletion(-) diff --git a/FluidNC/src/Spindles/OnOffSpindle.h b/FluidNC/src/Spindles/OnOffSpindle.h index b32fdded1..8e3a86f33 100644 --- a/FluidNC/src/Spindles/OnOffSpindle.h +++ b/FluidNC/src/Spindles/OnOffSpindle.h @@ -51,7 +51,6 @@ namespace Spindles { void group(Configuration::HandlerBase& handler) override { handler.item("direction_pin", _direction_pin); groupCommon(handler); - Spindle::group(handler); } virtual ~OnOff() {} From 2238d2697b128dbd9ceb4839a7913799424cee5f Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 28 Sep 2021 08:30:09 -1000 Subject: [PATCH 33/46] Added commentary --- FluidNC/src/Spindles/Laser.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/FluidNC/src/Spindles/Laser.h b/FluidNC/src/Spindles/Laser.h index 954c432ce..2c719734f 100644 --- a/FluidNC/src/Spindles/Laser.h +++ b/FluidNC/src/Spindles/Laser.h @@ -31,6 +31,9 @@ namespace Spindles { const char* name() const override { return "Laser"; } 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); From 416a7d8cd68f9d0659b601a95cf5a172e54d96ad Mon Sep 17 00:00:00 2001 From: bdring Date: Tue, 28 Sep 2021 14:11:50 -0500 Subject: [PATCH 34/46] Update VFDSpindle.cpp --- FluidNC/src/Spindles/VFDSpindle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/FluidNC/src/Spindles/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index dac7a68b2..59a181c56 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -334,7 +334,7 @@ namespace Spindles { setSpeed(dev_speed); } } - if (!use_delay_settings()) { + if (use_delay_settings()) { spindleDelay(state, speed); } else { // _sync_dev_speed is set by a callback that handles From a5e04b7fe068bce5a3df6a52a9311a0b1275d854 Mon Sep 17 00:00:00 2001 From: bdring Date: Thu, 30 Sep 2021 10:48:14 -0500 Subject: [PATCH 35/46] WIP Fixing laser mode issues. --- FluidNC/data/laser_test.nc | 5 + FluidNC/data/tmc2209_laser.yaml | 239 ++++++++++++++++++++++++++++ FluidNC/src/Spindles/PWMSpindle.cpp | 8 +- 3 files changed, 251 insertions(+), 1 deletion(-) create mode 100644 FluidNC/data/laser_test.nc create mode 100644 FluidNC/data/tmc2209_laser.yaml diff --git a/FluidNC/data/laser_test.nc b/FluidNC/data/laser_test.nc new file mode 100644 index 000000000..972f2dcab --- /dev/null +++ b/FluidNC/data/laser_test.nc @@ -0,0 +1,5 @@ +M4 S0 +G1 F100 +X10 S100 +X20 S200 +X30 S100 diff --git a/FluidNC/data/tmc2209_laser.yaml b/FluidNC/data/tmc2209_laser.yaml new file mode 100644 index 000000000..3281f2bcf --- /dev/null +++ b/FluidNC/data/tmc2209_laser.yaml @@ -0,0 +1,239 @@ +name: "TMC2209 XYYZ Laser" +board: "TMC2209 4x DK" + +stepping: + engine: RMT + idle_ms: 255 + dir_delay_us: 1 + pulse_us: 2 + disable_delay_us: 0 + +homing_init_lock: true + +axes: + shared_stepper_disable: gpio.25:high + + x: + steps_per_mm: 800.000 + max_rate: 5000.000 + acceleration: 100.000 + max_travel: 300.000 + soft_limits: false + homing: + cycle: 1 + 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: 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.26 + direction: gpio.27 + 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.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: gpio.34 + limit_all: NO_PIN + hard_limits: false + 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 + 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.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: gpio.39 + limit_all: NO_PIN + hard_limits: false + 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 + 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.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: gpio.36 + limit_all: NO_PIN + hard_limits: false + 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 + 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 + mosi: gpio.23 + sck: gpio.18 + +sdcard: + card_detect: NO_PIN + cs: gpio.5 + +probe: + pin: NO_PIN + +homing_init_lock: false + +Laser: + pwm_freq: 5000 + output_pin: gpio.4 + enable_pin: gpio.12 + disable_with_zero_speed: false + zero_speed_with_disable: false + tool: 100 + speeds: 0=0.000% 255=100.000% + \ No newline at end of file diff --git a/FluidNC/src/Spindles/PWMSpindle.cpp b/FluidNC/src/Spindles/PWMSpindle.cpp index 68e47aba2..5488a39ef 100644 --- a/FluidNC/src/Spindles/PWMSpindle.cpp +++ b/FluidNC/src/Spindles/PWMSpindle.cpp @@ -89,9 +89,15 @@ namespace Spindles { // spinning down. set_direction(state == SpindleState::Cw); } + // set_output must go first because of the way enable is used for level // converters on some boards. - set_output(dev_speed); + + // rate adjusted spindles (laser) in M4 set power via the stepper engine, not here + if (!isRateAdjusted() || state == SpindleState::Cw) { + set_output(dev_speed); + } + set_enable(state != SpindleState::Disable); spindleDelay(state, speed); } From 5bd8c052ffacd97758b2723927825b0c6202fc92 Mon Sep 17 00:00:00 2001 From: bdring Date: Thu, 30 Sep 2021 14:01:50 -0500 Subject: [PATCH 36/46] Issue #2 fix --- FluidNC/src/GCode.cpp | 3 ++- FluidNC/src/GCode.h | 4 ++-- FluidNC/src/Spindles/PWMSpindle.cpp | 2 +- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/FluidNC/src/GCode.cpp b/FluidNC/src/GCode.cpp index 2497a9a2a..e1cbd76d1 100644 --- a/FluidNC/src/GCode.cpp +++ b/FluidNC/src/GCode.cpp @@ -1326,7 +1326,8 @@ Error gc_execute_line(char* line, Print& client) { 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/Spindles/PWMSpindle.cpp b/FluidNC/src/Spindles/PWMSpindle.cpp index 5488a39ef..825975de7 100644 --- a/FluidNC/src/Spindles/PWMSpindle.cpp +++ b/FluidNC/src/Spindles/PWMSpindle.cpp @@ -94,7 +94,7 @@ namespace Spindles { // converters on some boards. // rate adjusted spindles (laser) in M4 set power via the stepper engine, not here - if (!isRateAdjusted() || state == SpindleState::Cw) { + if (!isRateAdjusted() || state != SpindleState::Ccw) { set_output(dev_speed); } From 9d68f2b4c9edf999fdd7b406d4738c1ee7d8b1f0 Mon Sep 17 00:00:00 2001 From: bdring Date: Thu, 30 Sep 2021 14:03:38 -0500 Subject: [PATCH 37/46] Update build-release.py --- build-release.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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)) From 3d8e82c2451f2d15d5b58f048aee500e5afac949 Mon Sep 17 00:00:00 2001 From: bdring Date: Thu, 30 Sep 2021 14:29:44 -0500 Subject: [PATCH 38/46] Issue #3 fixed See discussion https://discord.com/channels/780079161460916227/805613138916802570/892786277542412318 --- FluidNC/src/Spindles/PWMSpindle.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/FluidNC/src/Spindles/PWMSpindle.cpp b/FluidNC/src/Spindles/PWMSpindle.cpp index 825975de7..eafc7bbb9 100644 --- a/FluidNC/src/Spindles/PWMSpindle.cpp +++ b/FluidNC/src/Spindles/PWMSpindle.cpp @@ -90,11 +90,15 @@ namespace Spindles { 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. - // rate adjusted spindles (laser) in M4 set power via the stepper engine, not here - if (!isRateAdjusted() || state != SpindleState::Ccw) { + if (isRateAdjusted() && (state == SpindleState::Ccw)) { + dev_speed = offSpeed(); + set_output(dev_speed); + } else if (!isRateAdjusted() || state != SpindleState::Ccw) { set_output(dev_speed); } From e276fcc73071af44d2c703ddef1527633b013d3a Mon Sep 17 00:00:00 2001 From: bdring Date: Fri, 1 Oct 2021 08:46:45 -0500 Subject: [PATCH 39/46] Cleanup before merge --- FluidNC/data/laser_test.nc | 5 - FluidNC/data/tmc2209_laser.yaml | 239 ---------------------------- FluidNC/src/Spindles/PWMSpindle.cpp | 2 +- example_configs/tmc2209_laser.yaml | 157 +++++++++++++----- 4 files changed, 115 insertions(+), 288 deletions(-) delete mode 100644 FluidNC/data/laser_test.nc delete mode 100644 FluidNC/data/tmc2209_laser.yaml diff --git a/FluidNC/data/laser_test.nc b/FluidNC/data/laser_test.nc deleted file mode 100644 index 972f2dcab..000000000 --- a/FluidNC/data/laser_test.nc +++ /dev/null @@ -1,5 +0,0 @@ -M4 S0 -G1 F100 -X10 S100 -X20 S200 -X30 S100 diff --git a/FluidNC/data/tmc2209_laser.yaml b/FluidNC/data/tmc2209_laser.yaml deleted file mode 100644 index 3281f2bcf..000000000 --- a/FluidNC/data/tmc2209_laser.yaml +++ /dev/null @@ -1,239 +0,0 @@ -name: "TMC2209 XYYZ Laser" -board: "TMC2209 4x DK" - -stepping: - engine: RMT - idle_ms: 255 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -homing_init_lock: true - -axes: - shared_stepper_disable: gpio.25:high - - x: - steps_per_mm: 800.000 - max_rate: 5000.000 - acceleration: 100.000 - max_travel: 300.000 - soft_limits: false - homing: - cycle: 1 - 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: 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.26 - direction: gpio.27 - 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.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: gpio.34 - limit_all: NO_PIN - hard_limits: false - 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 - 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.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: gpio.39 - limit_all: NO_PIN - hard_limits: false - 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 - 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.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: gpio.36 - limit_all: NO_PIN - hard_limits: false - 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 - 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 - mosi: gpio.23 - sck: gpio.18 - -sdcard: - card_detect: NO_PIN - cs: gpio.5 - -probe: - pin: NO_PIN - -homing_init_lock: false - -Laser: - pwm_freq: 5000 - output_pin: gpio.4 - enable_pin: gpio.12 - disable_with_zero_speed: false - zero_speed_with_disable: false - tool: 100 - speeds: 0=0.000% 255=100.000% - \ No newline at end of file diff --git a/FluidNC/src/Spindles/PWMSpindle.cpp b/FluidNC/src/Spindles/PWMSpindle.cpp index eafc7bbb9..f62986d90 100644 --- a/FluidNC/src/Spindles/PWMSpindle.cpp +++ b/FluidNC/src/Spindles/PWMSpindle.cpp @@ -98,7 +98,7 @@ namespace Spindles { if (isRateAdjusted() && (state == SpindleState::Ccw)) { dev_speed = offSpeed(); set_output(dev_speed); - } else if (!isRateAdjusted() || state != SpindleState::Ccw) { + } else { set_output(dev_speed); } diff --git a/example_configs/tmc2209_laser.yaml b/example_configs/tmc2209_laser.yaml index 336e7b5cc..3281f2bcf 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 + zero_speed_with_disable: false tool: 100 speeds: 0=0.000% 255=100.000% \ No newline at end of file From fe7587fb052dc7a924c071346c05aea93f018271 Mon Sep 17 00:00:00 2001 From: bdring Date: Sat, 2 Oct 2021 14:46:01 -0500 Subject: [PATCH 40/46] Cleaned up the readme.md file changed YAML to "config file" --- README.md | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) 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 From f8aed655d390e82172e66c91529a85ef40a92e4c Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sat, 2 Oct 2021 10:30:21 -1000 Subject: [PATCH 41/46] Fixed WebUI access to NVS settings (again) --- .github/workflows/manual.yml | 2 +- FluidNC/src/Configuration/JsonGenerator.cpp | 14 ++-- FluidNC/src/ProcessSettings.cpp | 2 +- FluidNC/src/Settings.cpp | 8 +-- FluidNC/src/WebUI/JSONEncoder.cpp | 13 ++-- FluidNC/src/WebUI/WebSettings.cpp | 72 ++++++++++++--------- 6 files changed, 62 insertions(+), 49 deletions(-) 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/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/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index ee610b8f1..54e0946cb 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -563,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/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/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 feba15852..22d3d36f5 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -636,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(); @@ -1016,14 +1025,40 @@ namespace WebUI { void make_wifi_settings() { #ifdef ENABLE_WIFI - wifi_mode = new EnumSetting("WiFi mode", WEBSET, WA, "ESP116", "WiFi/Mode", WiFiFallback, &wifiModeOptions, 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, @@ -1033,10 +1068,10 @@ namespace WebUI { 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, @@ -1052,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, @@ -1072,31 +1106,7 @@ 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); From 5cfbb80b56f34fda7eda6605b3ec37236c4aafaf Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sat, 2 Oct 2021 22:31:41 -1000 Subject: [PATCH 42/46] Fix OLED stuff that crept into Devt Look in Config.h for how to enable it --- FluidNC/src/Config.h | 11 ++ FluidNC/src/Custom/oled.h | 3 - FluidNC/src/Custom/oled_basic.cpp | 198 +++++++++++++--------------- FluidNC/src/Custom/oled_io.cpp | 46 +++++++ FluidNC/src/Custom/oled_io.h | 9 ++ FluidNC/src/Custom/oled_tiny.cpp | 85 ++++++++++++ FluidNC/src/Main.cpp | 2 + FluidNC/src/Main.h | 3 + FluidNC/src/PinMapper.cpp | 45 +++++-- FluidNC/src/PinMapper.h | 8 +- FluidNC/src/Serial.cpp | 8 +- FluidNC/src/WebUI/Serial2Socket.cpp | 4 - FluidNC/src/WebUI/TelnetServer.cpp | 2 - FluidNC/src/WebUI/WifiConfig.cpp | 22 +--- platformio.ini | 52 +++----- 15 files changed, 303 insertions(+), 195 deletions(-) delete mode 100644 FluidNC/src/Custom/oled.h create mode 100644 FluidNC/src/Custom/oled_io.cpp create mode 100644 FluidNC/src/Custom/oled_io.h create mode 100644 FluidNC/src/Custom/oled_tiny.cpp 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/Custom/oled.h b/FluidNC/src/Custom/oled.h deleted file mode 100644 index c7faab607..000000000 --- a/FluidNC/src/Custom/oled.h +++ /dev/null @@ -1,3 +0,0 @@ -#pragma once -#include -extern SSD1306Wire oled; diff --git a/FluidNC/src/Custom/oled_basic.cpp b/FluidNC/src/Custom/oled_basic.cpp index cb5a6bf22..d44f33a2d 100644 --- a/FluidNC/src/Custom/oled_basic.cpp +++ b/FluidNC/src/Custom/oled_basic.cpp @@ -1,5 +1,3 @@ -#define INCLUDE_OLED_DISPLAY -#ifdef INCLUDE_OLED_DISPLAY // Copyright (c) 2020 - Bart Dring // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. @@ -14,121 +12,96 @@ 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! - - Library Infor: - https://github.com/ThingPulse/esp8266-oled-ssd1306 - - - Install to PlatformIO with this typed at the terminal - platformio lib install 2978 - - Add this to your machine definition file - #define DISPLAY_CODE_FILENAME "Custom/oled_basic.cpp" */ +#include "../Config.h" -// Include the correct display library +#ifdef INCLUDE_OLED_BASIC +# include "oled_io.h" +# include "../Main.h" // display_init() -# include # include "../Machine/MachineConfig.h" - # include "WiFi.h" # include "../WebUI/WebSettings.h" # include "../SettingsDefinitions.h" # include "../Report.h" # include "../Machine/Axes.h" # include "../Uart.h" -# ifndef OLED_ADDRESS -# define OLED_ADDRESS 0x3c -# endif - -# ifndef OLED_SDA -# define OLED_SDA GPIO_NUM_21 -# endif - -# ifndef OLED_SCL -# define OLED_SCL GPIO_NUM_22 -# endif - -# ifndef OLED_GEOMETRY -# define OLED_GEOMETRY GEOMETRY_64_48 -# endif -SSD1306Wire oled(OLED_ADDRESS, OLED_SDA, OLED_SCL, OLED_GEOMETRY, I2C_ONE, 400000); static TaskHandle_t oledUpdateTaskHandle = 0; // This displays the status of the ESP32 Radios...BT, WiFi, etc -void oledRadioInfo() { +static void oledRadioInfo() { String radio_addr = ""; String radio_name = ""; String radio_status = ""; # ifdef ENABLE_BLUETOOTH - if (config->_comms->_bluetoothConfig) { - radio_name = String("BT: ") + config->_comms->_bluetoothConfig->BTname(); + if (bt_enable->get()) { + radio_name = String("BT: ") + WebUI::bt_name->get(); + ; } # endif # ifdef ENABLE_WIFI - 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:") + config->_comms->_apConfig->_ssid; - radio_addr = WiFi.softAPIP().toString(); + 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 -# ifdef WIFI_OR_BLUETOOTH - if (WiFi.getMode() == WIFI_MODE_NULL) { - radio_name = "Radio Mode: None"; + if (radio_name == "") { + radio_name = "Radio Mode:Disabled"; } -# else - radio_name = "Radio Mode:Disabled"; -# endif - oled.setTextAlignment(TEXT_ALIGN_LEFT); - oled.setFont(ArialMT_Plain_10); + 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); + 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); + oled->drawString(55, 2, config->_comms->_bluetoothConfig ? radio_name : radio_addr); # endif } } -// Here changes begin Here changes begin Here changes begin Here changes begin Here changes begin -void draw_checkbox(int16_t x, int16_t y, int16_t width, int16_t height, bool checked) { +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 + oled->fillRect(x, y, width, height); // If log.0 else - oled.drawRect(x, y, width, height); // If log.1 + oled->drawRect(x, y, width, height); // If log.1 } -void oledDRO() { +static void oledDRO() { uint8_t oled_y_pos; //float wco[MAX_N_AXIS]; - oled.setTextAlignment(TEXT_ALIGN_LEFT); - oled.setFont(ArialMT_Plain_10); + oled->setTextAlignment(TEXT_ALIGN_LEFT); + oled->setFont(ArialMT_Plain_10); char axisVal[20]; - oled.drawString(80, 14, "L"); // Limit switch + 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); + 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"); + oled->drawString(60, 14, "M Pos"); } else { - oled.drawString(60, 14, "W Pos"); + oled->drawString(60, 14, "W Pos"); mpos_to_wpos(print_position); } @@ -137,12 +110,12 @@ void oledDRO() { 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_LEFT); + oled->drawString(0, oled_y_pos, axis_letter); // String('X') + ":"); - oled.setTextAlignment(TEXT_ALIGN_RIGHT); + oled->setTextAlignment(TEXT_ALIGN_RIGHT); snprintf(axisVal, 20 - 1, "%.3f", print_position[axis]); - oled.drawString(60, oled_y_pos, axisVal); + 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))); @@ -152,35 +125,35 @@ void oledDRO() { oled_y_pos = 14; if (config->_probe->exists()) { - oled.drawString(110, oled_y_pos, "P"); + 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"); + 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"); + 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"); + 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"); + oled->drawString(110, oled_y_pos, "D"); draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_safetyDoor.get()); oled_y_pos += 10; } } -void oledUpdate(void* pvParameters) { +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. @@ -188,39 +161,39 @@ void oledUpdate(void* pvParameters) { vTaskDelay(2500); uint16_t sd_file_ticker = 0; - oled.init(); - oled.flipScreenVertically(); + oled->init(); + oled->flipScreenVertically(); while (true) { - oled.clear(); + oled->clear(); String state_string = ""; - oled.setTextAlignment(TEXT_ALIGN_LEFT); - oled.setFont(ArialMT_Plain_16); - oled.drawString(0, 0, state_name()); + 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); + 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, 0, state_string); - oled.drawString(63, 12, config->_sdCard->filename()); + oled->drawString(63, 12, config->_sdCard->filename()); int progress = config->_sdCard->percent_complete(); // draw the progress bar - oled.drawProgressBar(0, 45, 120, 10, progress); + 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) + "%"); + oled->setFont(ArialMT_Plain_10); + oled->setTextAlignment(TEXT_ALIGN_CENTER); + oled->drawString(64, 25, String(progress) + "%"); } else if (sys.state == State::Alarm) { oledRadioInfo(); @@ -229,43 +202,48 @@ void oledUpdate(void* pvParameters) { oledRadioInfo(); } - oled.display(); + oled->display(); vTaskDelayUntil(&xLastWakeTime, xOledFrequency); } } void display_init() { - Uart0 << "Init OLED SDA:gpio." << OLED_SDA << " SCL:gpio." << OLED_SCL << '\n'; - oled.init(); + init_oled(0x3c, GPIO_NUM_14, GPIO_NUM_13, GEOMETRY_128_64); - oled.flipScreenVertically(); + oled->flipScreenVertically(); + oled->setTextAlignment(TEXT_ALIGN_LEFT); - oled.clear(); - oled.setLogBuffer(3, 10); + oled->clear(); + oled->display(); - oled.setTextAlignment(TEXT_ALIGN_LEFT); - - // String mach_name = config->_name; - //String mach_name = "Blaster"; - // remove characters from the end until the string fits - //while (oled.getStringWidth(mach_name) > 64) { - // mach_name = mach_name.substring(0, mach_name.length() - 1); - //} - //oled.drawString(0, 0, ".154"); - oled.fillCircle(32, 24, 10); - - oled.display(); -# if 0 xTaskCreatePinnedToCore(oledUpdate, // task "oledUpdateTask", // name for task - 4096, // size of task stack - NULL, // parameters - 1, // priority + 4096, // size of task stack + NULL, // parameters + 1, // priority &oledUpdateTaskHandle, CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core // core ); -# endif +} +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..125274923 --- /dev/null +++ b/FluidNC/src/Custom/oled_io.cpp @@ -0,0 +1,46 @@ +// 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! + + Library Info: + https://github.com/ThingPulse/esp8266-oled-ssd1306 + + + Install to PlatformIO with this typed at the terminal + platformio lib install 2978 + +*/ + +#include "../Config.h" + +#ifdef INCLUDE_OLED_IO +# include "oled_io.h" + +# include "../Pin.h" +# include "../PinMapper.h" +# include "../Uart.h" + +SSD1306Wire* oled; + +Pin oled_sda_pin; +Pin oled_scl_pin; +PinMapper oled_sda_pinmap; +PinMapper oled_scl_pinmap; +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/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/PinMapper.cpp b/FluidNC/src/PinMapper.cpp index 1f443b5f0..a97ca74b2 100644 --- a/FluidNC/src/PinMapper.cpp +++ b/FluidNC/src/PinMapper.cpp @@ -3,33 +3,39 @@ #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. 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 { + static const int N_PIN_MAPPINGS = 192; + public: - Pin* _mapping[256]; + static const int GPIO_LIMIT = 64; + + Pin* _mapping[N_PIN_MAPPINGS]; Mapping() { - for (int i = 0; i < 256; ++i) { + 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 + GPIO_LIMIT; } } return 0; } - void Release(pinnum_t idx) { _mapping[idx] = nullptr; } + void Release(pinnum_t idx) { _mapping[idx - GPIO_LIMIT] = nullptr; } static Mapping& instance() { static Mapping instance; @@ -74,15 +80,27 @@ PinMapper::~PinMapper() { } // Arduino compatibility functions, which basically forward the call to the mapper: -#if 0 void IRAM_ATTR digitalWrite(pinnum_t pin, uint8_t val) { - auto thePin = Mapping::instance()._mapping[pin]; + if (pin < Mapping::GPIO_LIMIT) { + return __digitalWrite(pin, val); + } + auto thePin = Mapping::instance()._mapping[pin - Mapping::GPIO_LIMIT]; if (thePin) { thePin->synchronousWrite(val); } } void IRAM_ATTR pinMode(pinnum_t pin, uint8_t mode) { + if (pin < Mapping::Mapping::GPIO_LIMIT) { + __pinMode(pin, mode); + return; + } + + auto thePin = Mapping::instance()._mapping[pin - Mapping::GPIO_LIMIT]; + if (!thePin) { + return; + } + Pins::PinAttributes attr = Pins::PinAttributes::None; if ((mode & OUTPUT) == OUTPUT) { attr = attr | Pins::PinAttributes::Output; @@ -97,14 +115,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 < Mapping::GPIO_LIMIT) { + return __digitalRead(pin); + } + auto thePin = Mapping::instance()._mapping[pin - Mapping::GPIO_LIMIT]; return (thePin) ? thePin->read() : 0; } -#endif 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/Serial.cpp b/FluidNC/src/Serial.cpp index edd5cca0e..e79ae40e3 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -49,14 +49,13 @@ #include "Protocol.h" // rtSafetyDoor etc #include "SDCard.h" #include "WebUI/InputBuffer.h" // XXX could this be a StringStream ? +#include "Main.h" // display() #include #include #include #include // portMUX_TYPE, TaskHandle_T -#include "Custom/oled.h" - portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED; static TaskHandle_t clientCheckTaskHandle = 0; @@ -248,10 +247,7 @@ InputClient* pollClients() { if (config->_sdCard->get_state() < SDCard::State::Busy) { client->_line[client->_linelen] = '\0'; client->_line_returned = true; - oled.clear(); - oled.println(client->_line); - oled.drawLogBuffer(0, 0); - oled.display(); + 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/WebUI/Serial2Socket.cpp b/FluidNC/src/WebUI/Serial2Socket.cpp index 609c2976d..cefe10e9f 100644 --- a/FluidNC/src/WebUI/Serial2Socket.cpp +++ b/FluidNC/src/WebUI/Serial2Socket.cpp @@ -2,7 +2,6 @@ // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #include "Serial2Socket.h" -#include "../Custom/oled.h" namespace WebUI { Serial_2_Socket Serial2Socket; @@ -25,9 +24,6 @@ namespace WebUI { _TXbufferSize = 0; _RXbufferSize = 0; _RXbufferpos = 0; - oled.clear(); - oled.fillRect(22, 14, 20, 20); - oled.display(); } void Serial_2_Socket::end() { diff --git a/FluidNC/src/WebUI/TelnetServer.cpp b/FluidNC/src/WebUI/TelnetServer.cpp index a23cd15eb..4e628fff0 100644 --- a/FluidNC/src/WebUI/TelnetServer.cpp +++ b/FluidNC/src/WebUI/TelnetServer.cpp @@ -7,8 +7,6 @@ #ifdef ENABLE_WIFI -#ifdef ENABLE_WIFI - namespace WebUI { Telnet_Server telnet_server; } diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index 6041c158e..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" @@ -19,8 +20,6 @@ WebUI::WiFiConfig wifi_config; # include # include -# include "../Custom/oled.h" - namespace WebUI { String WiFiConfig::_hostname = ""; bool WiFiConfig::_events_registered = false; @@ -220,20 +219,6 @@ namespace WebUI { return 2 * (RSSI + 100); } - void display_ip_tail(const IPAddress& ip) { - String ipa = ip.toString(); - auto dotpos = ipa.lastIndexOf('.'); // Last . - dotpos = ipa.substring(0, dotpos).lastIndexOf('.'); // Second to last . - auto tail = ipa.substring(dotpos + 1); - - oled.clear(); - oled.setFont(ArialMT_Plain_16); - oled.drawString(0, 0, tail); - oled.display(); - oled.setFont(ArialMT_Plain_10); - log_info("IP tail" << tail); - } - /* * Connect client to AP */ @@ -251,7 +236,7 @@ namespace WebUI { return false; case WL_CONNECTED: log_info("Connected - IP is " << WiFi.localIP().toString()); - display_ip_tail(WiFi.localIP()); + display("IP", WiFi.localIP().toString()); return true; default: if ((dot > 3) || (dot == 0)) { @@ -364,8 +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_tail(ip); - + display("IP", ip.toString()); return true; } diff --git a/platformio.ini b/platformio.ini index 6bdf3b15b..7dbdab1d1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -32,10 +32,21 @@ build_flags = -DCORE_DEBUG_LEVEL=0 -Wno-unused-variable -Wno-unused-function +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] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 platform = espressif32 board = esp32dev framework = arduino @@ -56,45 +67,20 @@ test_build_project_src = true [env:debug] build_type = debug -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 +lib_deps = ${common.lib_deps} [env:noradio] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 +lib_deps = ${common.lib_deps} [env:wifi] -lib_deps = - TMCStepper@>=0.7.0,<1.0.0 - ArduinoOTA - DNSServer - ESPmDNS - Update - WebServer - WiFi - WiFiClientSecure - thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 +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 - BluetoothSerial - thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 +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 - BluetoothSerial - ArduinoOTA - DNSServer - ESPmDNS - Update - WebServer - WiFi - WiFiClientSecure - thingpulse/ESP8266 and ESP32 OLED driver for SSD1306 displays@^4.2.1 +lib_deps = ${common.lib_deps} ${common.bt_deps} ${common.wifi_deps} + build_flags = ${common.build_flags} -DENABLE_BLUETOOTH -DENABLE_WIFI From 5c4a6c99837a28d015a2c1820063419312dbffb6 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sat, 2 Oct 2021 22:37:27 -1000 Subject: [PATCH 43/46] Removed dead code from oled_io.cpp --- FluidNC/src/Custom/oled_io.cpp | 24 ++++-------------------- 1 file changed, 4 insertions(+), 20 deletions(-) diff --git a/FluidNC/src/Custom/oled_io.cpp b/FluidNC/src/Custom/oled_io.cpp index 125274923..83ead7c49 100644 --- a/FluidNC/src/Custom/oled_io.cpp +++ b/FluidNC/src/Custom/oled_io.cpp @@ -2,45 +2,29 @@ // 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! + 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 "../Pin.h" -# include "../PinMapper.h" # include "../Uart.h" SSD1306Wire* oled; -Pin oled_sda_pin; -Pin oled_scl_pin; -PinMapper oled_sda_pinmap; -PinMapper oled_scl_pinmap; -void init_oled(uint8_t address, pinnum_t sda_gpio, pinnum_t scl_gpio, OLEDDISPLAY_GEOMETRY geometry) { +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 From 5e962d914f1907658b2f9a8091a993ac5eb40d11 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 3 Oct 2021 07:19:10 -1000 Subject: [PATCH 44/46] Derive pinmapper array size from GPIO_LIMIT .. per Stefan's suggestion Also added commentary and cleaned up some naming. --- FluidNC/src/PinMapper.cpp | 58 ++++++++++++++++++++------------ FluidNC/src/Pins/GPIOPinDetail.h | 3 +- 2 files changed, 39 insertions(+), 22 deletions(-) diff --git a/FluidNC/src/PinMapper.cpp b/FluidNC/src/PinMapper.cpp index a97ca74b2..f2853320f 100644 --- a/FluidNC/src/PinMapper.cpp +++ b/FluidNC/src/PinMapper.cpp @@ -1,4 +1,5 @@ #include "PinMapper.h" +#include "Pins/GPIOPinDetail.h" #include "Assert.h" @@ -7,19 +8,34 @@ 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. 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 { - static const int N_PIN_MAPPINGS = 192; +// 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. +namespace { + class PinMap { public: - static const int GPIO_LIMIT = 64; + static const int BOUNDARY = Pins::GPIOPinDetail::nGPIOPins; + private: + static const int N_PIN_MAPPINGS = 256 - BOUNDARY; + + public: Pin* _mapping[N_PIN_MAPPINGS]; - Mapping() { + PinMap() { for (int i = 0; i < N_PIN_MAPPINGS; ++i) { _mapping[i] = nullptr; } @@ -29,16 +45,16 @@ namespace { for (pinnum_t i = 0; i < N_PIN_MAPPINGS; ++i) { if (_mapping[i] == nullptr) { _mapping[i] = pin; - return i + GPIO_LIMIT; + return i + BOUNDARY; } } return 0; } - void Release(pinnum_t idx) { _mapping[idx - GPIO_LIMIT] = nullptr; } + void Release(pinnum_t idx) { _mapping[idx - BOUNDARY] = nullptr; } - static Mapping& instance() { - static Mapping instance; + static PinMap& instance() { + static PinMap instance; return instance; } }; @@ -49,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."); @@ -64,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); @@ -75,28 +91,28 @@ 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) { - if (pin < Mapping::GPIO_LIMIT) { + if (pin < PinMap::BOUNDARY) { return __digitalWrite(pin, val); } - auto thePin = Mapping::instance()._mapping[pin - Mapping::GPIO_LIMIT]; + 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 < Mapping::Mapping::GPIO_LIMIT) { + if (pin < PinMap::PinMap::BOUNDARY) { __pinMode(pin, mode); return; } - auto thePin = Mapping::instance()._mapping[pin - Mapping::GPIO_LIMIT]; + auto thePin = PinMap::instance()._mapping[pin - PinMap::BOUNDARY]; if (!thePin) { return; } @@ -119,9 +135,9 @@ void IRAM_ATTR pinMode(pinnum_t pin, uint8_t mode) { } int IRAM_ATTR digitalRead(pinnum_t pin) { - if (pin < Mapping::GPIO_LIMIT) { + if (pin < PinMap::BOUNDARY) { return __digitalRead(pin); } - auto thePin = Mapping::instance()._mapping[pin - Mapping::GPIO_LIMIT]; + auto thePin = PinMap::instance()._mapping[pin - PinMap::BOUNDARY]; return (thePin) ? thePin->read() : 0; } 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; From dcb5760c6ca2563c91601b49ac56c3c3c4579b97 Mon Sep 17 00:00:00 2001 From: bdring Date: Sun, 3 Oct 2021 13:01:09 -0500 Subject: [PATCH 45/46] Remove delay settings from laser --- FluidNC/src/Spindles/Laser.h | 1 + 1 file changed, 1 insertion(+) diff --git a/FluidNC/src/Spindles/Laser.h b/FluidNC/src/Spindles/Laser.h index 2c719734f..65d9c8ea3 100644 --- a/FluidNC/src/Spindles/Laser.h +++ b/FluidNC/src/Spindles/Laser.h @@ -27,6 +27,7 @@ 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"; } From 21794bd183c65f458f847c602e67366e360bac9c Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 3 Oct 2021 10:19:26 -1000 Subject: [PATCH 46/46] Allows builds without Git --- git-version.py | 75 ++++++++++++++++++++++++++++---------------------- 1 file changed, 42 insertions(+), 33 deletions(-) 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"