diff --git a/.github/ISSUE_TEMPLATE/problem.yml b/.github/ISSUE_TEMPLATE/problem.yml index b19bab2d5..aaa8c0081 100644 --- a/.github/ISSUE_TEMPLATE/problem.yml +++ b/.github/ISSUE_TEMPLATE/problem.yml @@ -5,7 +5,18 @@ labels: ["triage"] body: - type: markdown attributes: - value: Please fill in the forms below. The better the information you provide, the better we can help you. Information that you might think is irrelevant is often the key to solving the problem. **If we have to keep asking for information that you should have provided at the outset, we will become annoyed fairly quickly.** The amount of information that we ask for might seem excessive; it is not. We handle several issues a day. We cannot solve problems efficiently if we have to keep going back and forth for the basic information that we need. + value: | + Please search for answers on the [wiki](http://wiki.fluidnc.com) first. + If you don't find an answer, read [this](http://wiki.fluidnc.com/en/support/requesting_help) to help you fill in the forms below. The better the information you provide, the better we can help you. Information that you might think is irrelevant is often the key to solving the problem. **If we have to keep asking for information that you should have provided at the outset, we will become annoyed fairly quickly.** The amount of information that we ask for might seem excessive; it is not. We handle several issues a day. We cannot solve problems efficiently if we have to keep going back and forth for the basic information that we need. +- type: textarea + id: wiki-search + attributes: + label: Wiki Search Terms + description: Tell us some of the wiki search terms that you tried. This could help us improve the wiki. + placeholder: motor limit direction install configuration + validations: + required: true + - type: textarea id: controller-board attributes: @@ -61,7 +72,7 @@ body: Paste the startup messages here. You can see them by sending "$ss" from FluidTerm, WebUI Console, or any sender's console. Look through the messages for any MSG:ERR or MSG:WARN lines. They indicate problems in your config file. You might be able to solve the problem yourself. **Do not excerpt just the messages you think are revelant. - We need to see everything.** + We need to see everything.** [More info about startup messages](http://wiki.fluidnc.com/en/support/requesting_help#fluidnc-startup-messages) placeholder: render: text validations: @@ -80,6 +91,12 @@ body: placeholder: I did something, expected this, and that happened validations: required: true +- type: textarea + id: gcode-file + attributes: + label: GCode File + description: If the problem occurs when running a GCode file, attach it here (with a .txt extension), or paste it if it is short. If you can find a short file that exhibits the problem, it will be easier for us to debug. + placeholder: Paste or attach GCode here - type: textarea id: other-info attributes: diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml new file mode 100644 index 000000000..6ae7991f1 --- /dev/null +++ b/.github/workflows/ci.yml @@ -0,0 +1,86 @@ +name: FluidNC Continuous Integration +on: [push, pull_request] +jobs: + build: + strategy: + matrix: + os: + - ubuntu-latest + - macos-latest + - windows-latest + pio_env: + - noradio + - wifi + - bt + # - wifibt + # - debug + pio_env_variant: + - "" + # - "_s2" + # - "_s3" + runs-on: ${{ matrix.os }} + steps: + - uses: actions/checkout@v3 + - name: Set up Python + uses: actions/setup-python@v4 + with: + python-version: "3.9" + cache: "pip" + - name: Install PlatformIO + run: | + python -m pip install --upgrade pip + pip install -r requirements.txt + - name: Cache PlatformIO + uses: actions/cache@v3 + with: + path: ~/.platformio + key: platformio-${{ runner.os }} + - name: Build target ${{ matrix.pio_env }}${{ matrix.pio_env_variant }} + run: pio run -e ${{ matrix.pio_env }}${{ matrix.pio_env_variant }} + + tests: + strategy: + matrix: + include: + - os: ubuntu-latest + pio_env: tests + - os: macos-latest + pio_env: tests + - os: windows-latest + pio_env: tests_nosan + runs-on: ${{ matrix.os }} + steps: + - uses: actions/checkout@v3 + # Windows has issues running gtest code with the included gcc, so install + # MSYS2 and use that instead (remember to add it to the path) + - if: matrix.os == 'windows-latest' + name: Install MSYS2 (Windows) + uses: msys2/setup-msys2@v2 + with: + msystem: UCRT64 + location: D:\ + install: mingw-w64-ucrt-x86_64-gcc + - name: Set up Python + uses: actions/setup-python@v4 + with: + python-version: "3.9" + cache: "pip" + - name: Install PlatformIO + run: | + python -m pip install --upgrade pip + pip install -r requirements.txt + - name: Cache PlatformIO + uses: actions/cache@v3 + with: + path: ~/.platformio + key: platformio-${{ runner.os }} + + # Separate run task for Windows, since it has issues with the included gcc + - if: matrix.os == 'windows-latest' + name: Run tests (Windows) + run: | + $env:PATH = "D:\msys64\mingw64\bin;D:\msys64\usr\bin;D:\msys64\ucrt64\bin;" + $env:PATH + pio test -e ${{ matrix.pio_env }} -vv + - if: matrix.os != 'windows-latest' + name: Run tests + run: pio test -e ${{ matrix.pio_env }} -vv diff --git a/.github/workflows/manual.yml b/.github/workflows/manual.yml index 47597204e..2630c03b6 100644 --- a/.github/workflows/manual.yml +++ b/.github/workflows/manual.yml @@ -47,6 +47,18 @@ jobs: release/*.zip release/*.elf draft: True + - name: Deploy to fluidnc-releases + uses: datalbry/copy_folder_to_another_repo_action@1.0.0 + env: + API_TOKEN_GITHUB: ${{ secrets.RELEASE_COPY_TOKEN }} + with: + source_folder: 'release/current' + destination_repo: 'bdring/fluidnc-releases' + destination_branch: 'main' + destination_folder: releases/${{ github.event.inputs.tag }} + user_email: bdring@buildlog.net + user_name: 'Bart Dring' + commit_msg: Release ${{ github.event.inputs.tag }} # - name: Upload mac bundle # uses: actions/upload-artifact@v2 # with: diff --git a/.gitignore b/.gitignore index 3f8496990..e68197e31 100644 --- a/.gitignore +++ b/.gitignore @@ -30,3 +30,4 @@ build/ dist/ *.cppx *.hx +/compile_commands.json diff --git a/FluidNC/data/index.html.gz b/FluidNC/data/index.html.gz index 3f66fac04..f48937f2b 100644 Binary files a/FluidNC/data/index.html.gz and b/FluidNC/data/index.html.gz differ diff --git a/FluidNC/esp32/PwmPin.cpp b/FluidNC/esp32/PwmPin.cpp index 879deb99c..0a34164a4 100644 --- a/FluidNC/esp32/PwmPin.cpp +++ b/FluidNC/esp32/PwmPin.cpp @@ -72,6 +72,7 @@ static uint8_t calc_pwm_precision(uint32_t frequency) { } PwmPin::PwmPin(Pin& pin, uint32_t frequency) : _frequency(frequency) { + log_info("....PwnPin Create"); uint8_t bits = calc_pwm_precision(frequency); _period = (1 << bits) - 1; _channel = allocateChannel(); diff --git a/FluidNC/esp32/StartupLog.cpp b/FluidNC/esp32/StartupLog.cpp new file mode 100644 index 000000000..034e10d2b --- /dev/null +++ b/FluidNC/esp32/StartupLog.cpp @@ -0,0 +1,52 @@ +// Copyright (c) 2023 - Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#include "src/StartupLog.h" +#include "src/Protocol.h" // send_line() +#include + +// The startup log is stored in RTC RAM that is preserved across +// resets. That lets us show the previous startup log if the +// system panics and resets. + +// The size is limited by the size of RTC RAM minus system usage thereof +static const size_t _maxlen = 7000; +static RTC_NOINIT_ATTR char _messages[_maxlen]; +static RTC_NOINIT_ATTR size_t _len; +static bool _paniced; + +void StartupLog::init() { + if (esp_reset_reason() == ESP_RST_PANIC) { + _paniced = true; + } else { + _paniced = false; + _len = 0; + } +} +size_t StartupLog::write(uint8_t data) { + if (_paniced || _len >= _maxlen) { + return 0; + } + _messages[_len++] = (char)data; + return 1; +} +void StartupLog::dump(Channel& out) { + if (_paniced) { + log_error_to(out, "Showing startup log from previous panic"); + } + for (size_t i = 0; i < _len;) { + std::string line; + while (i < _len) { + char c = _messages[i++]; + if (c == '\n') { + break; + } + line += c; + } + log_to(out, line); + } +} + +StartupLog::~StartupLog() {} + +StartupLog startupLog; diff --git a/FluidNC/esp32/coredump.c b/FluidNC/esp32/coredump.c new file mode 100644 index 000000000..ccfd44446 --- /dev/null +++ b/FluidNC/esp32/coredump.c @@ -0,0 +1,35 @@ +// Copyright 2022 Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. +// +// Noop replacements for ESP-IDF coredump routines. +// This suppresses complaints about not being able to find a coredump partition. +// We don't want to waste space for such a partition, and the Arduino Framework +// enables coredumps. We override that by stubbing out these routines. + +#include +#include "esp_err.h" +#include "esp_private/panic_internal.h" +#include "esp_core_dump_summary_port.h" + +#ifdef __cplusplus +extern "C" { +#endif + +void esp_core_dump_init(void) {} + +void esp_core_dump_flash_init(void) {} +void esp_core_dump_to_flash(void* info) {} + +esp_err_t esp_core_dump_image_check(void) { + return ESP_ERR_NOT_FOUND; +} +esp_err_t esp_core_dump_image_get(size_t* out_addr, size_t* out_size) { + return ESP_ERR_NOT_FOUND; +} +esp_err_t esp_core_dump_image_erase(void) { + return ESP_OK; +} + +#ifdef __cplusplus +} +#endif diff --git a/FluidNC/esp32/gpio.cpp b/FluidNC/esp32/gpio.cpp index c71053e7c..2c95c4730 100644 --- a/FluidNC/esp32/gpio.cpp +++ b/FluidNC/esp32/gpio.cpp @@ -40,24 +40,10 @@ void gpio_mode(pinnum_t pin, bool input, bool output, bool pullup, bool pulldown } gpio_config(&conf); } -void IRAM_ATTR gpio_set_interrupt_type(pinnum_t pin, int mode) { - gpio_int_type_t type = GPIO_INTR_DISABLE; - // Do not use switch here because it is not IRAM_ATTR safe - if (mode == Pin::RISING_EDGE) { - type = GPIO_INTR_POSEDGE; - } else if (mode == Pin::FALLING_EDGE) { - type = GPIO_INTR_NEGEDGE; - } else if (mode == Pin::EITHER_EDGE) { - type = GPIO_INTR_ANYEDGE; - } - gpio_set_intr_type((gpio_num_t)pin, type); -} - +#if 0 void gpio_add_interrupt(pinnum_t pin, int mode, void (*callback)(void*), void* arg) { gpio_install_isr_service(ESP_INTR_FLAG_IRAM); // Will return an err if already called - gpio_set_interrupt_type(pin, mode); - gpio_num_t gpio = (gpio_num_t)pin; gpio_isr_handler_add(gpio, callback, arg); @@ -81,6 +67,100 @@ void gpio_route(pinnum_t pin, uint32_t signal) { gpio_set_direction(gpio, (gpio_mode_t)GPIO_MODE_DEF_OUTPUT); gpio_matrix_out(gpio, signal, 0, 0); } +#endif + +typedef uint64_t gpio_mask_t; + +// Can be used to display gpio_mask_t data for debugging +static const char* g_to_hex(gpio_mask_t n) { + static char hexstr[24]; + snprintf(hexstr, 22, "0x%llx", n); + return hexstr; +} + +static gpio_mask_t gpios_inverted = 0; // GPIOs that are active low +static gpio_mask_t gpios_interest = 0; // GPIOs with an action +static gpio_mask_t gpios_current = 0; // The last GPIO action events that were sent + +static int32_t gpio_next_event_ticks[GPIO_NUM_MAX + 1] = { 0 }; +static int32_t gpio_deltat_ticks[GPIO_NUM_MAX + 1] = { 0 }; + +// Do not send events for changes that occur too soon +static void gpio_set_rate_limit(int gpio_num, uint32_t ms) { + gpio_deltat_ticks[gpio_num] = ms * portTICK_PERIOD_MS; +} + +static inline gpio_mask_t get_gpios() { + return ((((uint64_t)REG_READ(GPIO_IN1_REG)) << 32) | REG_READ(GPIO_IN_REG)) ^ gpios_inverted; +} +static gpio_mask_t gpio_mask(int gpio_num) { + return 1ULL << gpio_num; +} +static inline bool gpio_is_active(int gpio_num) { + return get_gpios() & gpio_mask(gpio_num); +} +static void gpios_update(gpio_mask_t& gpios, int gpio_num, bool active) { + if (active) { + gpios |= gpio_mask(gpio_num); + } else { + gpios &= ~gpio_mask(gpio_num); + } +} + +static gpio_dispatch_t gpioActions[GPIO_NUM_MAX + 1] = { nullptr }; +static void* gpioArgs[GPIO_NUM_MAX + 1]; + +void gpio_set_action(int gpio_num, gpio_dispatch_t action, void* arg, bool invert) { + gpioActions[gpio_num] = action; + gpioArgs[gpio_num] = arg; + gpio_mask_t mask = gpio_mask(gpio_num); + gpios_update(gpios_interest, gpio_num, true); + gpios_update(gpios_inverted, gpio_num, invert); + gpio_set_rate_limit(gpio_num, 5); + bool active = gpio_is_active(gpio_num); + + // Set current to the opposite of the current state so the first poll will send the current state + gpios_update(gpios_current, gpio_num, !active); +} +void gpio_clear_action(int gpio_num) { + gpioActions[gpio_num] = nullptr; + gpioArgs[gpio_num] = nullptr; + gpios_update(gpios_interest, gpio_num, false); +} + +static void gpio_send_action(int gpio_num, bool active) { + auto end_ticks = gpio_next_event_ticks[gpio_num]; + int32_t this_ticks = int32_t(xTaskGetTickCount()); + if (end_ticks == 0 || ((this_ticks - end_ticks) > 0)) { + end_ticks = this_ticks + gpio_deltat_ticks[gpio_num]; + if (end_ticks == 0) { + end_ticks = 1; + } + gpio_next_event_ticks[gpio_num] = end_ticks; + + gpio_dispatch_t action = gpioActions[gpio_num]; + if (action) { + action(gpio_num, gpioArgs[gpio_num], active); + } + gpios_update(gpios_current, gpio_num, active); + } +} + +void poll_gpios() { + gpio_mask_t gpios_active = get_gpios(); + gpio_mask_t gpios_changed = (gpios_active ^ gpios_current) & gpios_interest; + if (gpios_changed) { + int zeros; + while ((zeros = __builtin_clzll(gpios_changed)) != 64) { + int gpio_num = 63 - zeros; + gpio_send_action(gpio_num, gpios_active & gpio_mask(gpio_num)); + // Remove bit from mask so clzll will find the next one + gpios_update(gpios_changed, gpio_num, false); + } + } +} + +// Support functions for gpio_dump static bool exists(gpio_num_t gpio) { if (gpio == 20) { // GPIO20 is listed in GPIO_PIN_MUX_REG[] but it is only @@ -378,7 +458,7 @@ struct gpio_matrix_t { { 228, "", "ig_in_func228", false }, { -1, "", "", false } }; -const char* out_sel_name(int function) { +static const char* out_sel_name(int function) { gpio_matrix_t* p; for (p = gpio_matrix; p->num != -1; ++p) { if (p->num == function) { @@ -388,7 +468,7 @@ const char* out_sel_name(int function) { return ""; } -void show_matrix(Print& out) { +static void show_matrix(Print& out) { gpio_matrix_t* p; for (p = gpio_matrix; p->num != -1; ++p) { uint32_t in_sel = gpio_in_sel(p->num); @@ -432,63 +512,3 @@ void gpio_dump(Print& out) { out << "Input Matrix\n"; show_matrix(out); } - -typedef uint64_t gpio_mask_t; -static gpio_mask_t gpio_inverts = 0; -static gpio_mask_t gpio_interest = 0; -static gpio_mask_t gpio_current = 0; -void IRAM_ATTR check_switches() { - gpio_mask_t gpio_this = (((uint64_t)REG_READ(GPIO_IN_REG)) << 32) | REG_READ(GPIO_IN1_REG); - if (gpio_this != gpio_current) { - gpio_mask_t gpio_changes = (gpio_this ^ gpio_current) & gpio_interest; - int bitno; - while (bitno = __builtin_ffsll(gpio_changes)) { - --bitno; - bool isActive = (gpio_this ^ gpio_inverts) & (1ULL << bitno); - // protocol_send_event_from_ISR(&pin_changes, (void*)(isActive ? bitno : -bitno)); - protocol_send_event_from_ISR(&motionCancelEvent, (void*)(isActive ? bitno : -bitno)); - } - gpio_current = gpio_this; - } - ++gpio_interest; -} -static gpio_dispatch_t gpioActions[GPIO_NUM_MAX + 1]; -static void* gpioArgs[GPIO_NUM_MAX + 1]; -void gpio_set_action(int gpio_num, gpio_dispatch_t action, void* arg, bool invert) { - gpioActions[gpio_num] = action; - gpioArgs[gpio_num] = arg; - gpio_mask_t mask = 1ULL << gpio_num; - gpio_interest |= mask; - if (invert) { - gpio_inverts |= mask; - } else { - gpio_inverts &= ~mask; - } -} -void gpio_clear_action(int gpio_num) { - gpioActions[gpio_num] = nullptr; - gpioArgs[gpio_num] = nullptr; - gpio_mask_t mask = 1ULL << gpio_num; - gpio_interest &= ~mask; -} -void poll_gpios() { - gpio_mask_t gpio_this = (((uint64_t)REG_READ(GPIO_IN1_REG)) << 32) | REG_READ(GPIO_IN_REG); - - gpio_mask_t gpio_changes = (gpio_this ^ gpio_current) & gpio_interest; - if (gpio_changes) { - gpio_mask_t gpio_active = gpio_this ^ gpio_inverts; - int zeros; - while ((zeros = __builtin_clzll(gpio_changes)) != 64) { - int gpio_num = 63 - zeros; - gpio_mask_t mask = 1ULL << gpio_num; - bool isActive = gpio_active & mask; - // Uart0 << gpio_num << " " << isActive << "\n"; - gpio_dispatch_t action = gpioActions[gpio_num]; - if (action) { - action(gpio_num, gpioArgs[gpio_num], isActive); - } - gpio_changes &= ~mask; - } - } - gpio_current = gpio_this; -} diff --git a/FluidNC/esp32/sdspi.cpp b/FluidNC/esp32/sdspi.cpp index dc507702f..c33f5cf8d 100644 --- a/FluidNC/esp32/sdspi.cpp +++ b/FluidNC/esp32/sdspi.cpp @@ -12,7 +12,7 @@ #define CHECK_EXECUTE_RESULT(err, str) \ do { \ if ((err) != ESP_OK) { \ - log_error(str << " code 0x" << to_hex(err)); \ + log_error(str << " code " << to_hex(err)); \ goto cleanup; \ } \ } while (0) diff --git a/FluidNC/esp32/tmc_spi.cpp b/FluidNC/esp32/tmc_spi.cpp index d0b700d4f..90cf4a056 100644 --- a/FluidNC/esp32/tmc_spi.cpp +++ b/FluidNC/esp32/tmc_spi.cpp @@ -43,7 +43,7 @@ // This is executed in the object context so it has access to class // data such as the CS pin that switchCSpin() uses void TMC2130Stepper::write(uint8_t reg, uint32_t data) { - log_verbose("TMC reg 0x" << to_hex(reg) << " write 0x" << to_hex(data)); + log_verbose("TMC reg " << to_hex(reg) << " write " << to_hex(data)); tmc_spi_bus_setup(); switchCSpin(0); @@ -88,7 +88,7 @@ uint32_t TMC2130Stepper::read(uint8_t reg) { data += (uint32_t)in[dummy_in_bytes + 4]; switchCSpin(1); - log_verbose("TMC reg 0x" << to_hex(reg) << " read 0x" << to_hex(data) << " status 0x" << to_hex(status)); + log_verbose("TMC reg " << to_hex(reg) << " read " << to_hex(data) << " status " << to_hex(status)); return data; } diff --git a/FluidNC/include/Driver/delay_usecs.h b/FluidNC/include/Driver/delay_usecs.h index 072713ae6..b5d24dd76 100644 --- a/FluidNC/include/Driver/delay_usecs.h +++ b/FluidNC/include/Driver/delay_usecs.h @@ -1,5 +1,7 @@ #include +extern uint32_t ticks_per_us; + void timing_init(); void spinUntil(int32_t endTicks); void delay_us(int32_t us); diff --git a/FluidNC/include/Driver/sdspi.h b/FluidNC/include/Driver/sdspi.h index c60ecbfbb..be038b019 100644 --- a/FluidNC/include/Driver/sdspi.h +++ b/FluidNC/include/Driver/sdspi.h @@ -4,4 +4,4 @@ bool sd_init_slot(uint32_t freq_hz, int cs_pin, int cd_pin = -1, int wp_pin = -1 void sd_unmount(); void sd_deinit_slot(); -std::error_code sd_mount(int max_files = 5); +std::error_code sd_mount(int max_files = 1); diff --git a/FluidNC/src/Channel.cpp b/FluidNC/src/Channel.cpp index e630d44e3..ea664de6e 100644 --- a/FluidNC/src/Channel.cpp +++ b/FluidNC/src/Channel.cpp @@ -4,8 +4,9 @@ #include "Channel.h" #include "Report.h" // report_gcode_modes #include "Machine/MachineConfig.h" // config -#include "Serial.h" // execute_realtime_command +#include "RealtimeCmd.h" // execute_realtime_command #include "Limits.h" +#include "Logging.h" void Channel::flushRx() { _linelen = 0; @@ -75,9 +76,23 @@ uint32_t Channel::setReportInterval(uint32_t ms) { _lastTool = 255; // Force GCodeState report return actual; } +static bool motionState() { + return sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog; +} + void Channel::autoReportGCodeState() { + // When moving, we suppress $G reports in which the only change is the motion mode + // (e.g. G0/G1/G2/G3 changes) because rapid-fire motion mode changes are fairly common. + // We would rather not issue a $G report after every GCode line. + // Similarly, F and S values can change rapidly, especially in laser programs. + // F and S values are also reported in ? status reports, so they will show up + // at the chosen periodic rate there. + if (motionState()) { + // Force the compare to succeed if the only change is the motion mode + _lastModal.motion = gc_state.modal.motion; + } if (memcmp(&_lastModal, &gc_state.modal, sizeof(_lastModal)) || _lastTool != gc_state.tool || - _lastSpindleSpeed != gc_state.spindle_speed || _lastFeedRate != gc_state.feed_rate) { + (!motionState() && (_lastSpindleSpeed != gc_state.spindle_speed || _lastFeedRate != gc_state.feed_rate))) { report_gcode_modes(*this); memcpy(&_lastModal, &gc_state.modal, sizeof(_lastModal)); _lastTool = gc_state.tool; @@ -85,21 +100,22 @@ void Channel::autoReportGCodeState() { _lastFeedRate = gc_state.feed_rate; } } -static bool motionState() { - return sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog; -} - void Channel::autoReport() { if (_reportInterval) { - auto limitState = limits_get_state(); - if (_reportWco || sys.state != _lastState || limitState != _lastLimits || + auto probeState = config->_probe->get_state(); + if (probeState != _lastProbe) { + report_recompute_pin_string(); + } + if (_reportWco || sys.state != _lastState || probeState != _lastProbe || _lastPinString != report_pin_string || (motionState() && (int32_t(xTaskGetTickCount()) - _nextReportTime) >= 0)) { if (_reportWco) { report_wco_counter = 0; } - _reportWco = false; - _lastState = sys.state; - _lastLimits = limitState; + _reportWco = false; + _lastState = sys.state; + _lastProbe = probeState; + _lastPinString = report_pin_string; + _nextReportTime = xTaskGetTickCount() + _reportInterval; report_realtime_status(*this); } @@ -111,6 +127,14 @@ void Channel::autoReport() { } } +void Channel::pin_event(uint32_t pinnum, bool active) { + try { + auto event_pin = _events.at(pinnum); + *_pin_values[pinnum] = active; + event_pin->trigger(active); + } catch (std::exception& ex) {} +} + Channel* Channel::pollLine(char* line) { handle(); while (1) { @@ -127,17 +151,51 @@ Channel* Channel::pollLine(char* line) { if (ch < 0) { break; } - if (realtimeOkay(ch) && is_realtime_command(ch)) { - execute_realtime_command(static_cast(ch), *this); + uint32_t cmd; + + int res = _utf8.decode(ch, cmd); + if (res == -1) { + log_debug("UTF8 decoding error"); + continue; + } + if (res == 0) { continue; } + // Otherwise res==1 and we have decoded a sequence so proceed + + if (cmd == PinACK) { + log_debug("ACK"); + _ackwait = false; + continue; + } + if (cmd == PinNAK) { + log_error("Channel device rejected config"); + log_debug("NAK"); + _ackwait = false; + continue; + } + + if (cmd >= PinLowFirst && cmd < PinLowLast) { + pin_event(cmd - PinLowFirst, false); + continue; + } + if (cmd >= PinHighFirst && cmd < PinHighLast) { + pin_event(cmd - PinHighFirst, true); + continue; + } + + if (realtimeOkay(cmd) && is_realtime_command(cmd)) { + execute_realtime_command(static_cast(cmd), *this); + continue; + } + if (!line) { // If we are not able to handle a line we save the character // until later - _queue.push(uint8_t(ch)); + _queue.push(uint8_t(cmd)); continue; } - if (line && lineComplete(line, ch)) { + if (lineComplete(line, cmd)) { return this; } } @@ -145,6 +203,43 @@ Channel* Channel::pollLine(char* line) { return nullptr; } +void Channel::setAttr(int index, bool* value, const std::string& attrString) { + if (value) { + _pin_values[index] = value; + } + int count = 0; + while (_ackwait && ++count < timeout) { + pollLine(NULL); + delay_ms(1); + } + if (count == timeout) { + log_error("Device not responding"); + } + log_msg_to(*this, attrString); + _ackwait = true; + log_debug(attrString); +} + +void Channel::out(const std::string& s) { + log_msg_to(*this, s); + // _channel->_ackwait = true; + log_debug(s); +} + +void Channel::ready() { +#if 0 + // At the moment this is unnecessary because initializing + // an input pin triggers an initial value event + if (!_pin_values.empty()) { + out("GET: io.*"); + } +#endif +} + +void Channel::registerEvent(uint8_t code, EventPin* obj) { + _events[code] = obj; +} + void Channel::ack(Error status) { if (status == Error::Ok) { log_to(*this, "ok"); @@ -160,3 +255,9 @@ void Channel::ack(Error status) { msg << static_cast(status); } } + +void Channel::print_msg(MsgLevel level, const char* msg) { + if (_message_level >= level) { + println(msg); + } +} diff --git a/FluidNC/src/Channel.h b/FluidNC/src/Channel.h index b67361eb3..de573ecfe 100644 --- a/FluidNC/src/Channel.h +++ b/FluidNC/src/Channel.h @@ -16,19 +16,40 @@ #pragma once -#include "Error.h" // Error -#include "GCode.h" // gc_modal_t -#include "Types.h" // State +#include "Error.h" // Error +#include "GCode.h" // gc_modal_t +#include "Types.h" // State +#include "RealtimeCmd.h" // Cmd +#include "UTF8.h" + +#include "Pins/PinAttributes.h" +#include "Machine/EventPin.h" + #include #include // TickType_T #include class Channel : public Stream { +private: + void pin_event(uint32_t pinnum, bool active); + + const int PinLowFirst = 0x100; + const int PinLowLast = 0x13f; + const int PinHighFirst = 0x140; + const int PinHighLast = 0x17f; + + const int PinACK = 0xB2; + const int PinNAK = 0xB3; + + const int timeout = 2000; + public: static const int maxLine = 255; + int _message_level = MsgLevelVerbose; + protected: - const char* _name; + std::string _name; char _line[maxLine]; size_t _linelen; bool _addCR = false; @@ -39,30 +60,47 @@ class Channel : public Stream { uint32_t _reportInterval = 0; int32_t _nextReportTime = 0; - gc_modal_t _lastModal; - uint8_t _lastTool; - float _lastSpindleSpeed; - float _lastFeedRate; - State _lastState; - MotorMask _lastLimits; + gc_modal_t _lastModal; + uint8_t _lastTool; + float _lastSpindleSpeed; + float _lastFeedRate; + State _lastState; + MotorMask _lastLimits; + bool _lastProbe; + std::string _lastPinString; bool _reportWco = true; CoordIndex _reportNgc = CoordIndex::End; + Cmd _last_rt_cmd; + + std::map _events; + std::map _pin_values; + + UTF8 _utf8; + public: Channel(const char* name, bool addCR = false) : _name(name), _linelen(0), _addCR(addCR) {} + Channel(const char* name, int num, bool addCR = false) { + _name = name; + _name += std::to_string(num), _linelen = 0, _addCR = addCR; + } virtual ~Channel() = default; - virtual void handle() {}; - virtual Channel* pollLine(char* line); - virtual void ack(Error status); - const char* name() { return _name; } + bool _ackwait = false; + + virtual void handle() {}; + virtual Channel* pollLine(char* line); + virtual void ack(Error status); + const std::string& name() { return _name; } // rx_buffer_available() is the number of bytes that can be sent without overflowing // a reception buffer, even if the system is busy. Channels that can handle external // input via an interrupt or other background mechanism should override it to return // the remaining space that mechanism has available. - virtual int rx_buffer_available() { return 0; }; + // The queue can handle more than 256 characters but we don't want it to get too + // large, so we report a limited size. + virtual int rx_buffer_available() { return std::max(0, 256 - int(_queue.size())); } // flushRx() discards any characters that have already been received. It is used // after a reset, so that anything already sent will not be processed. @@ -99,10 +137,18 @@ class Channel : public Stream { int peek() override { return -1; } int read() override { return -1; } - int available() override { return 0; } + int available() override { return _queue.size(); } + + virtual void print_msg(MsgLevel level, const char* msg); + + uint32_t setReportInterval(uint32_t ms); + uint32_t getReportInterval() { return _reportInterval; } + virtual void autoReport(); + void autoReportGCodeState(); - uint32_t setReportInterval(uint32_t ms); - uint32_t getReportInterval() { return _reportInterval; } - void autoReport(); - void autoReportGCodeState(); + // Pin extender functions + void out(const std::string& s); + void setAttr(int index, bool* valuep, const std::string& s); + void ready(); + void registerEvent(uint8_t code, EventPin* obj); }; diff --git a/FluidNC/src/Configuration/Completer.cpp b/FluidNC/src/Configuration/Completer.cpp index 2c0bae939..570f0439a 100644 --- a/FluidNC/src/Configuration/Completer.cpp +++ b/FluidNC/src/Configuration/Completer.cpp @@ -81,7 +81,7 @@ int num_initial_matches(char* key, int keylen, int matchnum, char* matchname) { nfound = completer._numMatches; } else { // Match NVS settings - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { if (isInitialSubstringCI(key, s->getName())) { if (matchname && nfound == matchnum) { strcpy(matchname, s->getName()); diff --git a/FluidNC/src/Configuration/Generator.h b/FluidNC/src/Configuration/Generator.h index f59c39c62..0cbb9c09f 100644 --- a/FluidNC/src/Configuration/Generator.h +++ b/FluidNC/src/Configuration/Generator.h @@ -4,6 +4,7 @@ #pragma once #include +#include #include "../Pin.h" #include "../Report.h" // report_gcode_modes() @@ -53,21 +54,18 @@ namespace Configuration { void item(const char* name, float& value, float minValue, float maxValue) override { send_item(name, std::to_string(value)); } void item(const char* name, std::vector& value) { - std::string s; if (value.size() == 0) { - s += "None"; + send_item(name, "None"); } else { + std::ostringstream s; + s.precision(2); const char* separator = ""; for (speedEntry n : value) { - s += separator; + s << separator << n.speed << "=" << std::fixed << n.percent << "%"; separator = " "; - s += std::to_string(n.speed); - s += '='; - s += std::to_string(n.percent); - s += '%'; } + send_item(name, s.str()); } - send_item(name, s); } void item(const char* name, UartData& wordLength, UartParity& parity, UartStop& stopBits) override { diff --git a/FluidNC/src/Configuration/JsonGenerator.cpp b/FluidNC/src/Configuration/JsonGenerator.cpp index 54597fc0d..d8b306932 100644 --- a/FluidNC/src/Configuration/JsonGenerator.cpp +++ b/FluidNC/src/Configuration/JsonGenerator.cpp @@ -58,6 +58,8 @@ namespace Configuration { { _encoder.begin_object(); _encoder.member("False", 0); + _encoder.end_object(); + _encoder.begin_object(); _encoder.member("True", 1); _encoder.end_object(); } diff --git a/FluidNC/src/Configuration/ParseException.h b/FluidNC/src/Configuration/ParseException.h index 173e01355..625a542e1 100644 --- a/FluidNC/src/Configuration/ParseException.h +++ b/FluidNC/src/Configuration/ParseException.h @@ -5,16 +5,16 @@ namespace Configuration { class ParseException { - int line_; - std::string description_; + int _linenum; + std::string _description; public: ParseException() = default; ParseException(const ParseException&) = default; - ParseException(int line, const char* description) : line_(line), description_(description) {} + ParseException(int linenum, const char* description) : _linenum(linenum), _description(description) {} - inline int LineNumber() const { return line_; } - inline const std::string& What() const { return description_; } + inline int LineNumber() const { return _linenum; } + inline const std::string& What() const { return _description; } }; } diff --git a/FluidNC/src/Configuration/Parser.cpp b/FluidNC/src/Configuration/Parser.cpp index 9cdecaa5a..635d726e0 100644 --- a/FluidNC/src/Configuration/Parser.cpp +++ b/FluidNC/src/Configuration/Parser.cpp @@ -1,4 +1,5 @@ // Copyright (c) 2021 - Stefan de Bruijn +// Copyright (c) 2023 - Dylan Knutson // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #include "Parser.h" @@ -7,125 +8,144 @@ #include "../EnumItem.h" #include "../Config.h" +#include "../string_util.h" #include #include // round +#include namespace Configuration { - Parser::Parser(const char* start, const char* end) : Tokenizer(start, end) {} + Parser::Parser(std::string_view yaml_string) : Tokenizer(yaml_string) {} void Parser::parseError(const char* description) const { // Attempt to use the correct position in the parser: - if (token_.keyEnd_) { - throw ParseException(line_, description); + if (!_token._key.empty()) { + throw ParseException(_linenum, description); } else { Tokenizer::ParseError(description); } } bool Parser::is(const char* expected) { - if (token_.state != TokenState::Matching || token_.keyStart_ == nullptr) { + if (_token._state != TokenState::Matching || _token._key.empty()) { return false; } auto len = strlen(expected); - if (len != (token_.keyEnd_ - token_.keyStart_)) { + if (len != _token._key.size()) { return false; } - bool result = !strncasecmp(expected, token_.keyStart_, len); + bool result = !strncasecmp(expected, _token._key.cbegin(), len); if (result) { - token_.state = TokenState::Matched; + _token._state = TokenState::Matched; } return result; } - StringRange Parser::stringValue() const { return StringRange(token_.sValueStart_, token_.sValueEnd_); } + // String values might have meaningful leading and trailing spaces so we avoid trimming the string (false) + std::string_view Parser::stringValue() const { return _token._value; } - bool Parser::boolValue() const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); - return str.equals("true"); - } + bool Parser::boolValue() const { return string_util::equal_ignore_case(string_util::trim(_token._value), "true"); } int Parser::intValue() const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); - int32_t value; - if (str.isInteger(value)) { - return value; + auto value_token = string_util::trim(_token._value); + int32_t int_value; + if (string_util::is_int(value_token, int_value)) { + return int_value; } - float fvalue; - if (str.isFloat(fvalue)) { - return lroundf(fvalue); + + // TODO(dymk) - is there a situation where we want to round a float + // to an int, rather than throwing? + float float_value; + if (string_util::is_float(value_token, float_value)) { + return lroundf(float_value); } + parseError("Expected an integer value"); return 0; } uint32_t Parser::uintValue() const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); - uint32_t value; - if (str.isUnsignedInteger(value)) { - return value; + auto token = string_util::trim(_token._value); + uint32_t uint_value; + if (string_util::is_uint(token, uint_value)) { + return uint_value; } - float fvalue; - if (str.isFloat(fvalue)) { - return lroundf(fvalue); + + float float_value; + if (string_util::is_float(token, float_value)) { + return lroundf(float_value); } + parseError("Expected an integer value"); return 0; } float Parser::floatValue() const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); - float value; - if (!str.isFloat(value)) { - parseError("Expected a float value like 123.456"); + auto token = string_util::trim(_token._value); + float float_value; + if (string_util::is_float(token, float_value)) { + return float_value; } - return value; + parseError("Expected a float value like 123.456"); + return NAN; } std::vector Parser::speedEntryValue() const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); - - std::vector value; - StringRange entryStr; - for (entryStr = str.nextWord(); entryStr.length(); entryStr = str.nextWord()) { - speedEntry entry; - StringRange speed = entryStr.nextWord('='); - if (!speed.length() || !speed.isUInteger(entry.speed)) { - log_error("Bad speed number " << speed.str()); - value.clear(); - break; + auto str = string_util::trim(_token._value); + + std::vector speed_entries; + + while (!str.empty()) { + auto next_ws_delim = str.find(' '); + auto entry_str = string_util::trim(str.substr(0, next_ws_delim)); + if (next_ws_delim == std::string::npos) { + next_ws_delim = str.length(); + } else { + next_ws_delim += 1; } - StringRange percent = entryStr.nextWord('%'); - if (!percent.length() || !percent.isFloat(entry.percent)) { - log_error("Bad speed percent " << percent.str()); - value.clear(); - break; + str.remove_prefix(next_ws_delim); + + speedEntry entry; + auto next_eq_delim = entry_str.find('='); + auto speed_str = string_util::trim(entry_str.substr(0, next_eq_delim)); + if (!string_util::is_uint(speed_str, entry.speed)) { + log_error("Bad speed number " << speed_str); + return {}; + } + entry_str.remove_prefix(next_eq_delim + 1); + + auto next_pct_delim = entry_str.find('%'); + auto percent_str = string_util::trim(entry_str.substr(0, next_pct_delim)); + if (!string_util::is_float(percent_str, entry.percent)) { + log_error("Bad speed percent " << percent_str); + return {}; } - value.push_back(entry); + entry_str.remove_prefix(next_pct_delim + 1); + + speed_entries.push_back(entry); } - if (!value.size()) + + if (!speed_entries.size()) { log_info("Using default speed map"); - return value; - } + } - Pin Parser::pinValue() const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); - return Pin::create(str); + return speed_entries; } + Pin Parser::pinValue() const { return Pin::create(string_util::trim(_token._value)); } + IPAddress Parser::ipValue() const { IPAddress ip; - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); - if (!ip.fromString(str.str().c_str())) { + if (!ip.fromString(std::string(string_util::trim(_token._value)).c_str())) { parseError("Expected an IP address like 192.168.0.100"); } return ip; } int Parser::enumValue(EnumItem* e) const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); + auto token = string_util::trim(_token._value); for (; e->name; ++e) { - if (str.equals(e->name)) { + if (string_util::equal_ignore_case(token, e->name)) { break; } } @@ -133,17 +153,17 @@ namespace Configuration { } void Parser::uartMode(UartData& wordLength, UartParity& parity, UartStop& stopBits) const { - auto str = StringRange(token_.sValueStart_, token_.sValueEnd_); + auto str = string_util::trim(_token._value); if (str.length() == 5 || str.length() == 3) { int32_t wordLenInt; - if (!str.substr(0, 1).isInteger(wordLenInt)) { + if (!string_util::is_int(str.substr(0, 1), wordLenInt)) { parseError("Uart mode should be specified as [Bits Parity Stopbits] like [8N1]"); } else if (wordLenInt < 5 || wordLenInt > 8) { parseError("Number of data bits for uart is out of range. Expected format like [8N1]."); } wordLength = UartData(int(UartData::Bits5) + (wordLenInt - 5)); - switch (str.begin()[1]) { + switch (str[1]) { case 'N': case 'n': parity = UartParity::None; @@ -162,11 +182,11 @@ namespace Configuration { } auto stop = str.substr(2, str.length() - 2); - if (stop.equals("1")) { + if (stop == "1") { stopBits = UartStop::Bits1; - } else if (stop.equals("1.5")) { + } else if (stop == "1.5") { stopBits = UartStop::Bits1_5; - } else if (stop.equals("2")) { + } else if (stop == "2") { stopBits = UartStop::Bits2; } else { parseError("Uart stopbits can only be 1, 1.5 or 2. Syntax is [8N1]"); diff --git a/FluidNC/src/Configuration/Parser.h b/FluidNC/src/Configuration/Parser.h index 4c9956830..c3c6a4016 100644 --- a/FluidNC/src/Configuration/Parser.h +++ b/FluidNC/src/Configuration/Parser.h @@ -1,11 +1,11 @@ // Copyright (c) 2021 - Stefan de Bruijn +// Copyright (c) 2023 - Dylan Knutson // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #pragma once #include "Tokenizer.h" #include "../Pin.h" -#include "../StringRange.h" #include "../EnumItem.h" #include "../UartTypes.h" #include "HandlerBase.h" @@ -19,11 +19,11 @@ namespace Configuration { void parseError(const char* description) const; public: - Parser(const char* start, const char* end); + Parser(std::string_view yaml_string); bool is(const char* expected); - StringRange stringValue() const; + std::string_view stringValue() const; bool boolValue() const; int intValue() const; uint32_t uintValue() const; diff --git a/FluidNC/src/Configuration/ParserHandler.h b/FluidNC/src/Configuration/ParserHandler.h index 2fb46e7a7..86470b3df 100644 --- a/FluidNC/src/Configuration/ParserHandler.h +++ b/FluidNC/src/Configuration/ParserHandler.h @@ -7,11 +7,10 @@ #include "Parser.h" #include "Configurable.h" #include "../System.h" +#include "parser_logging.h" #include -// #define DEBUG_VERBOSE_YAML_PARSER -// #define DEBUG_CHATTY_YAML_PARSER namespace Configuration { class ParserHandler : public Configuration::HandlerBase { private: @@ -24,18 +23,14 @@ namespace Configuration { // On entry, the token is for the section that invoked us. // We will handle following nodes with indents greater than entryIndent - int entryIndent = _parser.token_.indent_; -#ifdef DEBUG_CHATTY_YAML_PARSER - log_debug("Entered section " << name << " at indent " << entryIndent); -#endif + int entryIndent = _parser._token._indent; + log_parser_verbose("Entered section " << name << " at indent " << entryIndent); // The next token controls what we do next. If thisIndent is greater // than entryIndent, there are some subordinate tokens. _parser.Tokenize(); - int thisIndent = _parser.token_.indent_; -#ifdef DEBUG_VERBOSE_YAML_PARSER - log_debug("thisIndent " << _parser.key().str() << " " << thisIndent); -#endif + int thisIndent = _parser._token._indent; + log_parser_verbose("thisIndent " << _parser.key() << " " << thisIndent); // If thisIndent <= entryIndent, the section is empty - there are // no more-deeply-indented subordinate tokens. @@ -43,18 +38,13 @@ namespace Configuration { if (thisIndent > entryIndent) { // If thisIndent > entryIndent, the new token is the first token within // this section so we process tokens at the same level as thisIndent. - for (; _parser.token_.indent_ >= thisIndent; _parser.Tokenize()) { -#ifdef DEBUG_VERBOSE_YAML_PARSER - log_debug(" KEY " << _parser.key().str() << " state " << int(_parser.token_.state) << " indent " - << _parser.token_.indent_); -#endif - if (_parser.token_.indent_ > thisIndent) { - log_error("Skipping key " << _parser.key().str() << " indent " << _parser.token_.indent_ << " this indent " - << thisIndent); + for (; _parser._token._indent >= thisIndent; _parser.Tokenize()) { + log_parser_verbose(" KEY " << _parser.key() << " state " << int(_parser._token._state) << " indent " + << _parser._token._indent); + if (_parser._token._indent > thisIndent) { + log_error("Skipping key " << _parser.key() << " indent " << _parser._token._indent << " this indent " << thisIndent); } else { -#ifdef DEBUG_VERBOSE_YAML_PARSER - log_debug("Parsing key " << _parser.key().str()); -#endif + log_parser_verbose("Parsing key " << _parser.key()); try { section->group(*this); } catch (const AssertionFailed& ex) { @@ -65,14 +55,12 @@ namespace Configuration { sys.state = State::ConfigAlarm; } - if (_parser.token_.state == TokenState::Matching) { - log_warn("Ignored key " << _parser.key().str()); + if (_parser._token._state == TokenState::Matching) { + log_warn("Ignored key " << _parser.key()); } -#ifdef DEBUG_CHATTY_YAML_PARSER - if (_parser.token_.state == Configuration::TokenState::Matched) { - log_debug("Handled key " << _parser.key().str()); + if (_parser._token._state == Configuration::TokenState::Matched) { + log_parser_verbose("Handled key " << _parser.key()); } -#endif } } } @@ -82,12 +70,10 @@ namespace Configuration { // the caller will call Tokenize() to get a token, so we // "hold" the current token so that Tokenize() will // release that token instead of parsing ahead. - // _parser.token_.held = true; + // _parser._token.held = true; - _parser.token_.state = TokenState::Held; -#ifdef DEBUG_CHATTY_YAML_PARSER - log_debug("Left section at indent " << entryIndent << " holding " << _parser.key().str()); -#endif + _parser._token._state = TokenState::Held; + log_parser_verbose("Left section at indent " << entryIndent << " holding " << _parser.key()); _path.erase(_path.begin() + (_path.size() - 1)); } @@ -144,7 +130,7 @@ namespace Configuration { void item(const char* name, std::string& value, int minLength, int maxLength) override { if (_parser.is(name)) { - value = _parser.stringValue().str().c_str(); + value = _parser.stringValue(); } } diff --git a/FluidNC/src/Configuration/RuntimeSetting.cpp b/FluidNC/src/Configuration/RuntimeSetting.cpp index bfd80c17d..53cd96f6b 100644 --- a/FluidNC/src/Configuration/RuntimeSetting.cpp +++ b/FluidNC/src/Configuration/RuntimeSetting.cpp @@ -167,9 +167,14 @@ namespace Configuration { if (value.size() == 0) { log_to(out_, "None"); } else { + LogStream msg(out_, ""); + msg << setting_prefix(); + const char* separator = ""; for (speedEntry n : value) { - log_to(out_, "", n.speed << "=" << n.percent << "%") + msg << separator << n.speed << "=" << setprecision(2) << n.percent << "%"; + separator = " "; } + // The destructor sends the line when msg goes out of scope } } else { // It is distasteful to have this code that essentially duplicates diff --git a/FluidNC/src/Configuration/Tokenizer.cpp b/FluidNC/src/Configuration/Tokenizer.cpp index eb1d4a150..e4fc658df 100644 --- a/FluidNC/src/Configuration/Tokenizer.cpp +++ b/FluidNC/src/Configuration/Tokenizer.cpp @@ -1,155 +1,159 @@ // Copyright (c) 2021 - Stefan de Bruijn +// Copyright (c) 2023 - Dylan Knutson // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #include "Tokenizer.h" #include "ParseException.h" +#include "parser_logging.h" #include namespace Configuration { - void Tokenizer::skipToEol() { - while (!IsEndLine()) { - Inc(); + Tokenizer::Tokenizer(std::string_view yaml_string) : _remainder(yaml_string), _linenum(0), _token() {} + + bool Tokenizer::isWhiteSpace(char c) { return c == ' ' || c == '\t' || c == '\f' || c == '\r'; } + + bool Tokenizer::isIdentifierChar(char c) { + return (c >= 'a' && c <= 'z') || (c >= 'A' && c <= 'Z') || (c >= '0' && c <= '9') || c == '_'; + } + + void Tokenizer::ParseError(const char* description) const { throw ParseException(_linenum, description); } + + void Tokenizer::parseKey() { + // entry: first character is not space + // The first character in the line is neither # nor whitespace + if (!isIdentifierChar(_line.front())) { + ParseError("Invalid character"); + } + auto pos = _line.find_first_of(':'); + _token._key = _line.substr(0, pos); + while (isWhiteSpace(_token._key.back())) { + _token._key.remove_suffix(1); + } + if (pos == std::string_view::npos) { + std::string err = "Key "; + err += _token._key; + err += " must be followed by ':'"; + ParseError(err.c_str()); } - Inc(); + _line.remove_prefix(pos + 1); } - Tokenizer::Tokenizer(const char* start, const char* end) : current_(start), end_(end), start_(start), line_(0), token_() {} + // Sets _line to the next non-empty, non-comment line. + // Removes leading spaces setting _token._indent to their number + // Returns false at end of file + bool Tokenizer::nextLine() { + do { + _linenum++; + + // End of input + if (_remainder.empty()) { + _line = _remainder; + return false; + } + + // Get next line. The final line need not have a newline + auto pos = _remainder.find_first_of('\n'); + if (pos == std::string_view::npos) { + _line = _remainder; + _remainder.remove_prefix(_remainder.size()); + } else { + _line = _remainder.substr(0, pos); + _remainder.remove_prefix(pos + 1); + } + if (_line.empty()) { + continue; + } + + // Remove carriage return if present + if (_line.back() == '\r') { + _line.remove_suffix(1); + } + if (_line.empty()) { + continue; + } + + // Remove indentation and record the level + _token._indent = _line.find_first_not_of(' '); + if (_token._indent == std::string_view::npos) { + // Line containing only spaces + _line.remove_prefix(_line.size()); + continue; + } + _line.remove_prefix(_token._indent); + + // Disallow inital tabs + if (_line.front() == '\t') { + ParseError("Use spaces, not tabs, for indentation"); + } + + // Discard comment lines + if (_line.front() == '#') { // Comment till end of line + _line.remove_prefix(_line.size()); + } + } while (_line.empty()); + + return true; + } - void Tokenizer::ParseError(const char* description) const { throw ParseException(line_, description); } + void Tokenizer::parseValue() { + // Remove initial whitespace + while (!_line.empty() && isWhiteSpace(_line.front())) { + _line.remove_prefix(1); + } + + // Lines with no value are sections + if (_line.empty()) { + log_parser_verbose("Section " << _token._key); + // A key with nothing else is not necessarily a section - it could + // be an item whose value is the empty string + _token._value = {}; + return; + } + + auto delimiter = _line.front(); + if (delimiter == '"' || delimiter == '\'') { + // Value is quoted + _line.remove_prefix(1); + auto pos = _line.find_first_of(delimiter); + if (pos == std::string_view::npos) { + ParseError("Did not find matching delimiter"); + } + _token._value = _line.substr(0, pos); + _line.remove_prefix(pos + 1); + log_parser_verbose("StringQ " << _token._key << " " << _token._value); + } else { + // Value is not quoted + _token._value = _line; + log_parser_verbose("String " << _token._key << " " << _token._value); + } + } void Tokenizer::Tokenize() { // Release a held token - if (token_.state == TokenState::Held) { - token_.state = TokenState::Matching; -#ifdef DEBUG_VERBOSE_YAML_TOKENIZER - log_debug("Releasing " << key().str()); -#endif + if (_token._state == TokenState::Held) { + _token._state = TokenState::Matching; + log_parser_verbose("Releasing " << key()); return; } // Otherwise find the next token - token_.state = TokenState::Matching; + _token._state = TokenState::Matching; + // We parse 1 line at a time. Each time we get here, we can assume that the cursor // is at the start of the line. - parseAgain: - ++line_; - - int indent = 0; - - while (!Eof() && IsSpace()) { - Inc(); - ++indent; - } - token_.indent_ = indent; - - if (Eof()) { - token_.state = TokenState::Eof; - token_.indent_ = -1; - token_.keyStart_ = token_.keyEnd_ = current_; + if (nextLine()) { + parseKey(); + parseValue(); return; } - switch (Current()) { - case '\t': - ParseError("Use spaces, not tabs, for indentation"); - break; - - case '#': // Comment till end of line - Inc(); - while (!Eof() && !IsEndLine()) { - Inc(); - } - goto parseAgain; - - case '\r': - Inc(); - if (!Eof() && Current() == '\n') { - Inc(); - } // \r\n - goto parseAgain; - case '\n': - // \n without a preceding \r - Inc(); - goto parseAgain; - - default: - if (!IsIdentifierChar()) { - ParseError("Invalid character"); - } - - token_.keyStart_ = current_; - Inc(); - while (!Eof() && IsIdentifierChar()) { - Inc(); - } - token_.keyEnd_ = current_; - - // Skip whitespaces: - while (IsWhiteSpace()) { - Inc(); - } - - if (Current() != ':') { - std::string err = "Key "; - err += StringRange(token_.keyStart_, token_.keyEnd_).str().c_str(); - err += " must be followed by ':'"; - ParseError(err.c_str()); - } - Inc(); - - // Skip whitespaces after the colon: - while (IsWhiteSpace()) { - Inc(); - } - - // token_.indent_ = indent; - if (IsEndLine()) { -#ifdef DEBUG_VERBOSE_YAML_TOKENIZER - log_debug("Section " << StringRange(token_.keyStart_, token_.keyEnd_).str()); -#endif - // A key with nothing else is not necessarily a section - it could - // be an item whose value is the empty string - token_.sValueStart_ = current_; - token_.sValueEnd_ = current_; - Inc(); - } else { - if (Current() == '"' || Current() == '\'') { - auto delimiter = Current(); - - Inc(); - token_.sValueStart_ = current_; - while (!Eof() && Current() != delimiter && !IsEndLine()) { - Inc(); - } - token_.sValueEnd_ = current_; - if (Current() != delimiter) { - ParseError("Did not find matching delimiter"); - } - Inc(); -#ifdef DEBUG_VERBOSE_YAML_TOKENIZER - log_debug("StringQ " << StringRange(token_.keyStart_, token_.keyEnd_).str() << " " - << StringRange(token_.sValueStart_, token_.sValueEnd_).str()); -#endif - } else { - token_.sValueStart_ = current_; - while (!IsEndLine()) { - Inc(); - } - token_.sValueEnd_ = current_; - if (token_.sValueEnd_ != token_.sValueStart_ && token_.sValueEnd_[-1] == '\r') { - --token_.sValueEnd_; - } -#ifdef DEBUG_VERBOSE_YAML_TOKENIZER - log_debug("String " << StringRange(token_.keyStart_, token_.keyEnd_).str() << " " - << StringRange(token_.sValueStart_, token_.sValueEnd_).str()); -#endif - } - skipToEol(); - } - break; - } // switch + + // End of file + _token._state = TokenState::Eof; + _token._indent = -1; + _token._key = {}; } } diff --git a/FluidNC/src/Configuration/Tokenizer.h b/FluidNC/src/Configuration/Tokenizer.h index 8ae4254a8..aefe91d08 100644 --- a/FluidNC/src/Configuration/Tokenizer.h +++ b/FluidNC/src/Configuration/Tokenizer.h @@ -1,94 +1,46 @@ // Copyright (c) 2021 - Stefan de Bruijn +// Copyright (c) 2023 - Dylan Knutson // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #pragma once #include "TokenState.h" #include "../Config.h" +#include namespace Configuration { class Tokenizer { - const char* current_; - const char* end_; + std::string_view _remainder; - void skipToEol(); - - inline void Inc() { - if (current_ != end_) { - ++current_; - } - } - inline char Current() const { return Eof() ? '\0' : (*current_); } - - inline bool IsAlpha() { - char c = Current(); - return (c >= 'a' && c <= 'z') || (c >= 'A' && c <= 'Z'); - } - - inline bool IsSpace() { return Current() == ' '; } - - inline bool IsWhiteSpace() { - if (Eof()) { - return false; - } - char c = Current(); - return c == ' ' || c == '\t' || c == '\f' || c == '\r'; - } - - inline bool IsIdentifierChar() { return IsAlpha() || IsDigit() || Current() == '_'; } - - inline bool IsEndLine() { return Eof() || Current() == '\n'; } - - inline bool IsDigit() { - char c = Current(); - return (c >= '0' && c <= '9'); - } - - inline char ToLower(char c) { return (c >= 'A' && c <= 'Z') ? (char)(c + 32) : c; } - - inline bool EqualsCaseInsensitive(const char* input) { - const char* tmp = current_; - while (ToLower(*input) == ToLower(Current()) && *input != '\0') { - Inc(); - ++input; - } - - bool isSame = *input == '\0'; // Everything till the end of the input string is the same - current_ = tmp; // Restore situation - return isSame; - } + bool isWhiteSpace(char c); + bool isIdentifierChar(char c); + bool nextLine(); + void parseKey(); + void parseValue(); public: - const char* start_; - int line_; + int _linenum; + std::string_view _line; // Results: struct TokenData { // The initial value for indent is -1, so when ParserHandler::enterSection() // is called to handle the top level of the YAML config file, tokens at // indent 0 will be processed. - TokenData() : - keyStart_(nullptr), keyEnd_(nullptr), indent_(-1), state(TokenState::Bof), sValueStart_(nullptr), sValueEnd_(nullptr) {} - - const char* keyStart_; - const char* keyEnd_; - int indent_; + TokenData() : _key({}), _value({}), _indent(-1), _state(TokenState::Bof) {} + std::string_view _key; + std::string_view _value; + int _indent; - TokenState state = TokenState::Bof; - - const char* sValueStart_; - const char* sValueEnd_; - } token_; + TokenState _state = TokenState::Bof; + } _token; void ParseError(const char* description) const; - inline bool Eof() const { return current_ == end_; } - public: - Tokenizer(const char* start, const char* end); - void Tokenize(); - - inline StringRange key() const { return StringRange(token_.keyStart_, token_.keyEnd_); } + Tokenizer(std::string_view yaml_string); + void Tokenize(); + inline std::string_view key() const { return _token._key; } }; } diff --git a/FluidNC/src/Configuration/parser_logging.h b/FluidNC/src/Configuration/parser_logging.h new file mode 100644 index 000000000..8aba3283a --- /dev/null +++ b/FluidNC/src/Configuration/parser_logging.h @@ -0,0 +1,9 @@ +#pragma once + +static constexpr bool verbose_debugging = false; +#define log_parser_verbose(x) \ + do { \ + if (verbose_debugging) { \ + log_debug(x); \ + } \ + } while (0) diff --git a/FluidNC/src/Control.cpp b/FluidNC/src/Control.cpp index b993c573f..2e8848405 100644 --- a/FluidNC/src/Control.cpp +++ b/FluidNC/src/Control.cpp @@ -9,13 +9,15 @@ Control::Control() { // The SafetyDoor pin must be defined first because it is checked explicity in safety_door_ajar() _pins.push_back(new ControlPin(&safetyDoorEvent, "safety_door_pin", 'D')); - _pins.push_back(new ControlPin(&resetEvent, "reset_pin", 'R')); + _pins.push_back(new ControlPin(&rtResetEvent, "reset_pin", 'R')); _pins.push_back(new ControlPin(&feedHoldEvent, "feed_hold_pin", 'H')); _pins.push_back(new ControlPin(&cycleStartEvent, "cycle_start_pin", 'S')); _pins.push_back(new ControlPin(¯o0Event, "macro0_pin", '0')); _pins.push_back(new ControlPin(¯o1Event, "macro1_pin", '1')); _pins.push_back(new ControlPin(¯o2Event, "macro2_pin", '2')); _pins.push_back(new ControlPin(¯o3Event, "macro3_pin", '3')); + _pins.push_back(new ControlPin(&faultPinEvent, "fault_pin", 'F')); + _pins.push_back(new ControlPin(&faultPinEvent, "estop_pin", 'E')); } void Control::init() { diff --git a/FluidNC/src/ControlPin.cpp b/FluidNC/src/ControlPin.cpp index 721a7adac..763c9a5ff 100644 --- a/FluidNC/src/ControlPin.cpp +++ b/FluidNC/src/ControlPin.cpp @@ -1,3 +1,12 @@ #include "ControlPin.h" -namespace Machine {} +namespace Machine { + void ControlPin::init() { + if (_pin.undefined()) { + return; + } + _pin.report(_legend); + _pin.setAttr(Pin::Attr::Input); + _pin.registerEvent(static_cast(this)); + } +}; diff --git a/FluidNC/src/ControlPin.h b/FluidNC/src/ControlPin.h index 6eaa2bd61..c9e451fe2 100644 --- a/FluidNC/src/ControlPin.h +++ b/FluidNC/src/ControlPin.h @@ -1,18 +1,21 @@ #pragma once #include "Pin.h" -#include // IRAM_ATTR #include "Machine/EventPin.h" namespace Machine { - class ControlPin : public Machine::EventPin { + class ControlPin : public EventPin { private: const char _letter; // The name that appears in init() messages and the name of the configuration item public: - ControlPin(Event* event, const char* legend, char letter) : EventPin(event, legend, &_pin), _letter(letter) {} + ControlPin(Event* event, const char* legend, char letter) : EventPin(event, legend), _letter(letter) {} + + void init(); Pin _pin; + bool get() { return _pin.read(); } + char letter() { return _letter; }; ~ControlPin(); diff --git a/FluidNC/src/CoolantControl.cpp b/FluidNC/src/CoolantControl.cpp index eb96ec1d3..38583f108 100644 --- a/FluidNC/src/CoolantControl.cpp +++ b/FluidNC/src/CoolantControl.cpp @@ -53,9 +53,11 @@ void CoolantControl::write(CoolantState state) { bool pinState = state.Mist; _mist.synchronousWrite(pinState); } + + _previous_state = state; } -// Directly called by coolant_init(), coolant_set_state(), and mc_reset(), which can be at +// Directly called by coolant_init(), coolant_set_state(), which can be at // an interrupt-level. No report flag set, but only called by routines that don't need it. void CoolantControl::stop() { CoolantState disable = {}; @@ -68,11 +70,13 @@ void CoolantControl::stop() { // parser program end, and g-code parser CoolantControl::sync(). void CoolantControl::set_state(CoolantState state) { - if (sys.abort) { - return; // Block during abort. + if (sys.abort || (_previous_state.Mist == state.Mist && _previous_state.Flood == state.Flood)) { + return; // Block during abort or if no change } write(state); - delay_msec(_delay_ms, DwellMode::SysSuspend); + + if (state.Mist || state.Flood) // ignore delay on turn off + delay_msec(_delay_ms, DwellMode::SysSuspend); } void CoolantControl::off() { diff --git a/FluidNC/src/CoolantControl.h b/FluidNC/src/CoolantControl.h index 4726e4fb0..c4c368947 100644 --- a/FluidNC/src/CoolantControl.h +++ b/FluidNC/src/CoolantControl.h @@ -13,6 +13,8 @@ class CoolantControl : public Configuration::Configurable { uint32_t _delay_ms = 0; + CoolantState _previous_state = {}; + void write(CoolantState state); public: diff --git a/FluidNC/src/Error.cpp b/FluidNC/src/Error.cpp index ed590ab0e..e6be271a4 100644 --- a/FluidNC/src/Error.cpp +++ b/FluidNC/src/Error.cpp @@ -57,6 +57,7 @@ std::map ErrorNames = { { Error::FsFailedBusy, "Device is busy" }, { Error::FsFailedDelDir, "Failed to delete directory" }, { Error::FsFailedDelFile, "Failed to delete file" }, + { Error::FsFailedRenameFile, "Failed to rename file" }, { Error::FsFailedCreateFile, "Failed to create file" }, { Error::FsFailedFormat, "Failed to format filesystem" }, { Error::NumberRange, "Number out of range for setting" }, @@ -67,10 +68,12 @@ std::map ErrorNames = { { Error::AuthenticationFailed, "Authentication failed!" }, { Error::Eol, "End of line" }, { Error::Eof, "End of file" }, + { Error::Reset, "System Reset" }, { Error::AnotherInterfaceBusy, "Another interface is busy" }, { Error::BadPinSpecification, "Bad Pin Specification" }, { Error::JogCancelled, "Jog Cancelled" }, { Error::ConfigurationInvalid, "Configuration is invalid. Check boot messages for ERR's." }, { Error::UploadFailed, "File Upload Failed" }, { Error::DownloadFailed, "File Download Failed" }, + { Error::ReadOnlySetting, "Read-only setting" }, }; diff --git a/FluidNC/src/Error.h b/FluidNC/src/Error.h index afa12da81..a400522e4 100644 --- a/FluidNC/src/Error.h +++ b/FluidNC/src/Error.h @@ -61,6 +61,7 @@ enum class Error : uint8_t { FsFailedBusy = 67, // Filesystem is busy FsFailedDelDir = 68, FsFailedDelFile = 69, + FsFailedRenameFile = 70, NumberRange = 80, // Setting number range problem InvalidValue = 81, // Setting string problem FsFailedCreateFile = 82, @@ -71,6 +72,7 @@ enum class Error : uint8_t { AuthenticationFailed = 110, Eol = 111, Eof = 112, // Not necessarily an error + Reset = 113, AnotherInterfaceBusy = 120, JogCancelled = 130, BadPinSpecification = 150, @@ -78,6 +80,7 @@ enum class Error : uint8_t { ConfigurationInvalid = 152, UploadFailed = 160, DownloadFailed = 161, + ReadOnlySetting = 162, }; const char* errorString(Error errorNumber); diff --git a/FluidNC/src/FileStream.cpp b/FluidNC/src/FileStream.cpp index 4d5cfcbed..4ac48e3a6 100644 --- a/FluidNC/src/FileStream.cpp +++ b/FluidNC/src/FileStream.cpp @@ -3,7 +3,6 @@ #include "FileStream.h" #include "Machine/MachineConfig.h" // config-> -#include "Driver/localfs.h" std::string FileStream::path() { return _fpath.c_str(); diff --git a/FluidNC/src/FluidPath.cpp b/FluidNC/src/FluidPath.cpp index 610d6e8d8..8748339af 100644 --- a/FluidNC/src/FluidPath.cpp +++ b/FluidNC/src/FluidPath.cpp @@ -3,8 +3,9 @@ #include "FluidPath.h" #include "Driver/sdspi.h" -#include "Driver/localfs.h" #include "Config.h" +#include "Error.h" +#include "HashFS.h" int FluidPath::_refcnt = 0; diff --git a/FluidNC/src/FluidPath.h b/FluidNC/src/FluidPath.h index 0701eceba..3bdf1ce3d 100644 --- a/FluidNC/src/FluidPath.h +++ b/FluidNC/src/FluidPath.h @@ -3,6 +3,7 @@ #include #include #include +#include "Driver/localfs.h" namespace stdfs = std::filesystem; diff --git a/FluidNC/src/GCode.cpp b/FluidNC/src/GCode.cpp index 942947104..1ea5e722a 100644 --- a/FluidNC/src/GCode.cpp +++ b/FluidNC/src/GCode.cpp @@ -172,6 +172,7 @@ Error gc_execute_line(char* line) { bool syncLaser = false; bool disableLaser = false; bool laserIsMotion = false; + bool nonmodalG38 = false; // Used for G38.6-9 auto n_axis = config->_axes->_numberAxis; float coord_data[MAX_N_AXIS]; // Used by WCO-related commands @@ -320,6 +321,10 @@ Error gc_execute_line(char* line) { probeExplicit = true; axis_command = AxisCommand::MotionMode; + if (mantissa >= 60) { + nonmodalG38 = true; + mantissa -= 40; + } switch (mantissa) { case 20: gc_block.modal.motion = Motion::ProbeToward; @@ -794,7 +799,7 @@ Error gc_execute_line(char* line) { if (bitnum_is_false(value_words, GCodeWord::F)) { FAIL(Error::GcodeUndefinedFeedRate); } - if (gc_block.modal.units == Units::Inches) { + if (!nonmodalG38 && gc_block.modal.units == Units::Inches) { gc_block.values.f *= MM_PER_INCH; } } else { @@ -822,7 +827,7 @@ Error gc_execute_line(char* line) { // - In units per mm mode: If F word passed, ensure value is in mm/min, otherwise push last state value. if (gc_state.modal.feed_rate == FeedRate::UnitsPerMin) { // Last state is also G94 if (bitnum_is_true(value_words, GCodeWord::F)) { - if (gc_block.modal.units == Units::Inches) { + if (!nonmodalG38 && gc_block.modal.units == Units::Inches) { gc_block.values.f *= MM_PER_INCH; } } else { @@ -895,7 +900,7 @@ Error gc_execute_line(char* line) { // [12. Set length units ]: N/A // Pre-convert XYZ coordinate values to millimeters, if applicable. - if (gc_block.modal.units == Units::Inches) { + if (!nonmodalG38 && gc_block.modal.units == Units::Inches) { for (size_t idx = 0; idx < n_axis; idx++) { // Axes indices are consistent, so loop may be used. if ((idx < A_AXIS || idx > C_AXIS) && bitnum_is_true(axis_words, idx)) { gc_block.values.xyz[idx] *= MM_PER_INCH; @@ -1034,7 +1039,7 @@ Error gc_execute_line(char* line) { // NOTE: G53 is never active with G28/30 since they are in the same modal group. if (gc_block.non_modal_command != NonModal::AbsoluteOverride) { // Apply coordinate offsets based on distance mode. - if (gc_block.modal.distance == Distance::Absolute) { + if (!nonmodalG38 && gc_block.modal.distance == Distance::Absolute) { gc_block.values.xyz[idx] += block_coord_system[idx] + gc_state.coord_offset[idx]; if (idx == TOOL_LENGTH_OFFSET_AXIS) { gc_block.values.xyz[idx] += gc_state.tool_length_offset; @@ -1152,7 +1157,7 @@ Error gc_execute_line(char* line) { FAIL(Error::GcodeInvalidTarget); // [Invalid target] } // Convert radius value to proper units. - if (gc_block.modal.units == Units::Inches) { + if (!nonmodalG38 && gc_block.modal.units == Units::Inches) { gc_block.values.r *= MM_PER_INCH; } /* We need to calculate the center of the circle that has the designated radius and passes @@ -1246,7 +1251,7 @@ Error gc_execute_line(char* line) { } clear_bits(value_words, (bitnum_to_mask(GCodeWord::I) | bitnum_to_mask(GCodeWord::J) | bitnum_to_mask(GCodeWord::K))); // Convert IJK values to proper units. - if (gc_block.modal.units == Units::Inches) { + if (!nonmodalG38 && gc_block.modal.units == Units::Inches) { for (size_t idx = 0; idx < n_axis; idx++) { // Axes indices are consistent, so loop may be used to save flash space. if (ijk_words & bitnum_to_mask(idx)) { gc_block.values.ijk[idx] *= MM_PER_INCH; @@ -1366,16 +1371,11 @@ Error gc_execute_line(char* line) { if (!blockIsFeedrateMotion) { // If the new mode is not a feedrate move (G1/2/3) we want the laser off disableLaser = true; - // If we are changing from a feedrate move to a non-feedrate move, - // we must sync the planner and then update the laser state - if (stateIsFeedrateMotion) { - syncLaser = true; - } } // 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. // TODO: Check sync conditions for M3 enabled motions that don't enter the planner. (zero length). - if (blockIsFeedrateMotion && axis_words && (axis_command == AxisCommand::MotionMode)) { + if (axis_words && (axis_command == AxisCommand::MotionMode)) { laserIsMotion = true; } else { // M3 constant power laser requires planner syncs to update the laser when changing between @@ -1410,14 +1410,10 @@ Error gc_execute_line(char* line) { pl_data->feed_rate = gc_state.feed_rate; // Record data for planner use. // [4. Set spindle speed ]: if ((gc_state.spindle_speed != gc_block.values.s) || syncLaser) { - if (gc_state.modal.spindle != SpindleState::Disable) { - if (!laserIsMotion) { - if (sys.state != State::CheckMode) { - protocol_buffer_synchronize(); - spindle->setState(gc_state.modal.spindle, disableLaser ? 0 : (uint32_t)gc_block.values.s); - report_ovr_counter = 0; // Set to report change immediately - } - } + if (gc_state.modal.spindle != SpindleState::Disable && !laserIsMotion && sys.state != State::CheckMode) { + protocol_buffer_synchronize(); + spindle->setState(gc_state.modal.spindle, disableLaser ? 0 : (uint32_t)gc_block.values.s); + report_ovr_counter = 0; // Set to report change immediately } gc_state.spindle_speed = gc_block.values.s; // Update spindle speed state. } @@ -1624,6 +1620,9 @@ Error gc_execute_line(char* line) { // As far as the parser is concerned, the position is now == target. In reality the // motion control system might still be processing the action and the real tool position // in any intermediate location. + if (sys.abort) { + return Error::Reset; + } if (gc_update_pos == GCUpdatePos::Target) { copyAxes(gc_state.position, gc_block.values.xyz); } else if (gc_update_pos == GCUpdatePos::System) { diff --git a/FluidNC/src/GCode.h b/FluidNC/src/GCode.h index 8b2e45335..1307de8e1 100644 --- a/FluidNC/src/GCode.h +++ b/FluidNC/src/GCode.h @@ -159,7 +159,7 @@ enum class IoControl : uint8_t { SetAnalogImmediate = 6, // M68 }; -static const int MaxUserDigitalPin = 4; +static const int MaxUserDigitalPin = 8; static const int MaxUserAnalogPin = 4; // Modal Group G8: Tool length offset diff --git a/FluidNC/src/HashFS.cpp b/FluidNC/src/HashFS.cpp new file mode 100644 index 000000000..1c2b8e729 --- /dev/null +++ b/FluidNC/src/HashFS.cpp @@ -0,0 +1,119 @@ +#include "HashFS.h" +#include "FileStream.h" + +#include + +std::map HashFS::localFsHashes; + +static char hexNibble(int i) { + return "0123456789ABCDEF"[i & 0xf]; +} + +static Error hashFile(const std::filesystem::path& ipath, std::string& str) { // No ESP command + mbedtls_md_context_t ctx; + + uint8_t shaResult[32]; + + try { + FileStream inFile { ipath, "r" }; + uint8_t buf[512]; + size_t len; + + mbedtls_md_init(&ctx); + mbedtls_md_setup(&ctx, mbedtls_md_info_from_type(MBEDTLS_MD_SHA256), 0); + mbedtls_md_starts(&ctx); + while ((len = inFile.read(buf, 512)) > 0) { + mbedtls_md_update(&ctx, buf, len); + } + mbedtls_md_finish(&ctx, shaResult); + mbedtls_md_free(&ctx); + } catch (const Error err) { + log_debug("Cannot hash file " << ipath); + return Error::FsFailedOpenFile; + } + + str = '"'; + for (int i = 0; i < 32; i++) { + uint8_t b = shaResult[i]; + str += hexNibble(b >> 4); + str += hexNibble(b); + } + str += '"'; + + return Error::Ok; +} + +void HashFS::report_change() { + log_msg("Files changed"); +} + +void HashFS::delete_file(const std::filesystem::path& path, bool report) { + localFsHashes.erase(path.filename()); + if (report) { + report_change(); + } +} + +bool HashFS::file_is_hashed(const std::filesystem::path& path) { + int count = 0; + for (auto it = path.begin(); it != path.end(); ++it) { + ++count; + } + // The first component is "/", then e.g. "littlefs", then + // the filename. If there are more components, there is + // a subdirectory and we do not hash it. + if (count != 3) { + return false; + } + auto fsname = *++path.begin(); + return fsname == "littlefs" || fsname == "spiffs" || fsname == "localfs"; +} + +void HashFS::rehash_file(const std::filesystem::path& path, bool report) { + if (file_is_hashed(path)) { + std::string hash; + if (hashFile(path, hash) != Error::Ok) { + delete_file(path, false); + } else { + localFsHashes[path.filename()] = hash; + } + } + if (report) { + report_change(); + } +} +void HashFS::rename_file(const std::filesystem::path& ipath, const std::filesystem::path& opath, bool report) { + delete_file(ipath, false); + rehash_file(opath, report); +} + +void HashFS::hash_all() { + localFsHashes.clear(); + + std::error_code ec; + FluidPath lfspath { "", localfsName, ec }; + if (ec) { + return; + } + + auto iter = stdfs::directory_iterator { lfspath, ec }; + if (ec) { + log_error(lfspath << " " << ec.message()); + return; + } + for (auto const& dir_entry : iter) { + if (!dir_entry.is_directory()) { + rehash_file(dir_entry, false); + } + } +} +std::string HashFS::hash(const std::filesystem::path& path) { + if (file_is_hashed(path)) { + std::map::iterator it; + it = localFsHashes.find(path.filename()); + if (it != localFsHashes.end()) { + return it->second; + } + } + return std::string(); +} diff --git a/FluidNC/src/HashFS.h b/FluidNC/src/HashFS.h new file mode 100644 index 000000000..24ff294f4 --- /dev/null +++ b/FluidNC/src/HashFS.h @@ -0,0 +1,20 @@ +#pragma once +#include +#include +#include + +class HashFS { +public: + static std::map localFsHashes; + + static bool file_is_hashed(const std::filesystem::path& path); + static void delete_file(const std::filesystem::path& path, bool report = true); + static void rehash_file(const std::filesystem::path& path, bool report = true); + static void rename_file(const std::filesystem::path& ipath, const std::filesystem::path& opath, bool report = true); + static void hash_all(); + static void report_change(); + + static std::string hash(const std::filesystem::path& path); + +private: +}; diff --git a/FluidNC/src/I2SOut.cpp b/FluidNC/src/I2SOut.cpp index 3cf336f0a..d94480f64 100644 --- a/FluidNC/src/I2SOut.cpp +++ b/FluidNC/src/I2SOut.cpp @@ -887,7 +887,7 @@ int i2s_out_init(i2s_out_init_t& init_param) { "I2SOutTask", 4096, NULL, - 1, + 3, nullptr, CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core ); diff --git a/FluidNC/src/InputFile.cpp b/FluidNC/src/InputFile.cpp index 99f974a02..7878e8956 100644 --- a/FluidNC/src/InputFile.cpp +++ b/FluidNC/src/InputFile.cpp @@ -88,6 +88,7 @@ void InputFile::stopJob() { //Report print stopped _notifyf("File print canceled", "Reset during file job at line: %d", getLineNumber()); log_info("Reset during file job at line: " << getLineNumber()); + _progress = ""; allChannels.kill(this); } diff --git a/FluidNC/src/Jog.cpp b/FluidNC/src/Jog.cpp index f50844897..1768a8bdf 100644 --- a/FluidNC/src/Jog.cpp +++ b/FluidNC/src/Jog.cpp @@ -12,6 +12,8 @@ // Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog. // cancelledInflight will be set to true if was not added to parser due to a cancelJog. Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* cancelledInflight) { + config->_kinematics->constrain_jog(gc_block->values.xyz, pl_data, gc_state.position); + // Initialize planner data struct for jogging motions. // NOTE: Spindle and coolant are allowed to fully function with overrides during a jog. pl_data->feed_rate = gc_block->values.f; @@ -19,8 +21,6 @@ Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* can pl_data->is_jog = true; pl_data->line_number = gc_block->values.n; - constrainToSoftLimits(gc_block->values.xyz); - if (!mc_linear(gc_block->values.xyz, pl_data, gc_state.position)) { return Error::JogCancelled; } diff --git a/FluidNC/src/Kinematics/Cartesian.cpp b/FluidNC/src/Kinematics/Cartesian.cpp index 359c1baf6..00b1318bd 100644 --- a/FluidNC/src/Kinematics/Cartesian.cpp +++ b/FluidNC/src/Kinematics/Cartesian.cpp @@ -18,6 +18,237 @@ namespace Kinematics { } } + // Check that the arc does not exceed the soft limits using a fast + // algorithm that requires no transcendental functions. + // caxes[] depends on the plane selection via G17, G18, and G19. caxes[0] is the first + // circle plane axis, caxes[1] is the second circle plane axis, and caxes[2] is the + // orthogonal plane. So for G17 mode, caxes[] is { 0, 1, 2} for { X, Y, Z}. G18 is {2, 0, 1} i.e. {Z, X, Y}, and G19 is {1, 2, 0} i.e. {Y, Z, X} + bool Cartesian::invalid_arc( + float* target, plan_line_data_t* pl_data, float* position, float center[3], float radius, size_t caxes[3], bool is_clockwise_arc) { + pl_data->limits_checked = true; + + auto axes = config->_axes; + // Handle the orthognal axis first to get it out of the way. + size_t the_axis = caxes[2]; + if (axes->_axis[the_axis]->_softLimits) { + float amin = std::min(position[the_axis], target[the_axis]); + if (amin < limitsMinPosition(the_axis)) { + limit_error(the_axis, amin); + return true; + } + float amax = std::max(position[the_axis], target[the_axis]); + if (amax > limitsMaxPosition(the_axis)) { + limit_error(the_axis, amax); + return true; + } + } + + bool limited[2] = { axes->_axis[caxes[0]]->_softLimits, axes->_axis[caxes[1]]->_softLimits }; + + // If neither axis of the circular plane has limits enabled, skip the computation + if (!(limited[0] || limited[1])) { + return false; + } + + // The origin for this calculation's coordinate system is at the center of the arc. + // The 0 and 1 entries are for the circle plane + // and the 2 entry is the orthogonal (linear) direction + + float s[2], e[2]; // Start and end of arc in the circle plane, relative to center + + // Depending on the arc direction, set the arc start and end points relative + // to the arc center. Afterwards, end is always counterclockwise relative to + // start, thus simplifying the following decision tree. + if (is_clockwise_arc) { + s[0] = target[caxes[0]] - center[0]; + s[1] = target[caxes[1]] - center[1]; + e[0] = position[caxes[0]] - center[0]; + e[1] = position[caxes[1]] - center[1]; + } else { + s[0] = position[caxes[0]] - center[0]; + s[1] = position[caxes[1]] - center[1]; + e[0] = target[caxes[0]] - center[0]; + e[1] = target[caxes[1]] - center[1]; + } + + // Axis crossings - plus and minus caxes[0] and caxes[1] + bool p[2] = { false, false }; + bool m[2] = { false, false }; + + // The following decision tree determines whether the arc crosses + // the horizontal and vertical axes of the circular plane in the + // positive and negative half planes. There are ways to express + // it in fewer lines of code by converting to alternate + // representations like angles, but this way is computationally + // efficient since it avoids any use of transcendental functions. + // Every path through this decision tree is either 4 or 5 simple + // comparisons. + if (e[1] >= 0) { // End in upper half plane + if (e[0] > 0) { // End in quadrant 0 - X+ Y+ + if (s[1] >= 0) { // Start in upper half plane + if (s[0] > 0) { // Start in quadrant 0 - X+ Y+ + if (s[0] <= e[0]) { // wraparound + p[0] = p[1] = m[0] = m[1] = true; + } + } else { // Start in quadrant 1 - X- Y+ + m[0] = m[1] = p[0] = true; + } + } else { // Start in lower half plane + if (s[0] > 0) { // Start in quadrant 3 - X+ Y- + p[0] = true; + } else { // Start in quadrant 2 - X- Y- + m[1] = p[0] = true; + } + } + } else { // End in quadrant 1 - X- Y+ + if (s[1] >= 0) { // Start in upper half plane + if (s[0] > 0) { // Start in quadrant 0 - X+ Y+ + p[1] = true; + } else { // Start in quadrant 1 - X- Y+ + if (s[0] <= e[0]) { // wraparound + p[0] = p[1] = m[0] = m[1] = true; + } + } + } else { // Start in lower half plane + if (s[0] > 0) { // Start in quadrant 3 - X+ Y- + p[0] = p[1] = true; + } else { // Start in quadrant 2 - X- Y- + m[1] = p[0] = p[1] = true; + } + } + } + } else { // e[1] < 0 - end in lower half plane + if (e[0] > 0) { // End in quadrant 3 - X+ Y+ + if (s[1] >= 0) { // Start in upper half plane + if (s[0] > 0) { // Start in quadrant 0 - X+ Y+ + p[1] = m[0] = m[1] = true; + } else { // Start in quadrant 1 - X- Y+ + m[0] = m[1] = true; + } + } else { // Start in lower half plane + if (s[0] > 0) { // Start in quadrant 3 - X+ Y- + if (s[0] >= e[0]) { // wraparound + p[0] = p[1] = m[0] = m[1] = true; + } + } else { // Start in quadrant 2 - X- Y- + m[1] = true; + } + } + } else { // End in quadrant 2 - X- Y+ + if (s[1] >= 0) { // Start in upper half plane + if (s[0] > 0) { // Start in quadrant 0 - X+ Y+ + p[1] = m[0] = true; + } else { // Start in quadrant 1 - X- Y+ + m[0] = true; + } + } else { // Start in lower half plane + if (s[0] > 0) { // Start in quadrant 3 - X+ Y- + p[0] = p[1] = m[0] = true; + } else { // Start in quadrant 2 - X- Y- + if (s[0] >= e[0]) { // wraparound + p[0] = p[1] = m[0] = m[1] = true; + } + } + } + } + } + // Now check limits based on arc endpoints and axis crossings + for (size_t a = 0; a < 2; ++a) { + the_axis = caxes[a]; + if (limited[a]) { + // If we crossed the axis in the positive half plane, the + // maximum extent along that axis is at center + radius. + // Otherwise it is the maximum coordinate of the start and + // end positions. Similarly for the negative half plane + // and the minimum extent. + float amin = m[a] ? center[a] - radius : std::min(target[the_axis], position[the_axis]); + if (amin < limitsMinPosition(the_axis)) { + limit_error(the_axis, amin); + return true; + } + float amax = p[a] ? center[a] + radius : std::max(target[the_axis], position[the_axis]); + if (amax > limitsMaxPosition(the_axis)) { + limit_error(the_axis, amax); + return true; + } + } + } + return false; + } + + void Cartesian::constrain_jog(float* target, plan_line_data_t* pl_data, float* position) { + auto axes = config->_axes; + auto n_axis = config->_axes->_numberAxis; + + float* current_position = get_mpos(); + MotorMask lim_pin_state = limits_get_state(); + + for (int axis = 0; axis < n_axis; axis++) { + auto axisSetting = axes->_axis[axis]; + // If the axis is moving from the current location and soft limits are on. + if (axisSetting->_softLimits && target[axis] != current_position[axis]) { + // When outside the axis range, only small nudges to clear switches are allowed + bool move_positive = target[axis] > current_position[axis]; + if ((!move_positive && (current_position[axis] < limitsMinPosition(axis))) || + (move_positive && (current_position[axis] > limitsMaxPosition(axis)))) { + // only allow a nudge if a switch is active + if (bitnum_is_false(lim_pin_state, Machine::Axes::motor_bit(axis, 0)) && + bitnum_is_false(lim_pin_state, Machine::Axes::motor_bit(axis, 1))) { + target[axis] = current_position[axis]; // cancel the move on this axis + log_debug("Soft limit violation on " << Machine::Axes::_names[axis]); + continue; + } + float jog_dist = target[axis] - current_position[axis]; + + MotorMask axisMotors = Machine::Axes::axes_to_motors(1 << axis); + bool posLimited = bits_are_true(Machine::Axes::posLimitMask, axisMotors); + bool negLimited = bits_are_true(Machine::Axes::negLimitMask, axisMotors); + + // if jog is positive and only the positive switch is active, then kill the move + // if jog is negative and only the negative switch is active, then kill the move + if (posLimited != negLimited) { // XOR, because ambiguous (both) is OK + if ((negLimited && (jog_dist < 0)) || (posLimited && (jog_dist > 0))) { + target[axis] = current_position[axis]; // cancel the move on this axis + log_debug("Jog into active switch blocked on " << Machine::Axes::_names[axis]); + continue; + } + } + + auto nudge_max = axisSetting->_motors[0]->_pulloff; + if (abs(jog_dist) > nudge_max) { + target[axis] = (jog_dist >= 0) ? current_position[axis] + nudge_max : current_position[axis] + nudge_max; + log_debug("Jog amount limited when outside soft limits") + } + continue; + } + + if (target[axis] < limitsMinPosition(axis)) { + target[axis] = limitsMinPosition(axis); + } else if (target[axis] > limitsMaxPosition(axis)) { + target[axis] = limitsMaxPosition(axis); + } else { + continue; + } + log_debug("Jog constrained to axis range"); + } + } + pl_data->limits_checked = true; + } + + bool Cartesian::invalid_line(float* cartesian) { + auto axes = config->_axes; + auto n_axis = config->_axes->_numberAxis; + + for (int axis = 0; axis < n_axis; axis++) { + float coordinate = cartesian[axis]; + if (axes->_axis[axis]->_softLimits && (coordinate < limitsMinPosition(axis) || coordinate > limitsMaxPosition(axis))) { + limit_error(axis, coordinate); + return true; + } + } + return false; + } + bool Cartesian::cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) { // Motor space is cartesian space, so we do no transform. return mc_move_motors(target, pl_data); @@ -28,9 +259,10 @@ namespace Kinematics { copyAxes(cartesian, motors); } - void Cartesian::transform_cartesian_to_motors(float* motors, float* cartesian) { + bool Cartesian::transform_cartesian_to_motors(float* motors, float* cartesian) { // Motor space is cartesian space, so we do no transform. copyAxes(motors, cartesian); + return true; } bool Cartesian::canHome(AxisMask axisMask) { @@ -73,6 +305,10 @@ namespace Kinematics { } } + bool Cartesian::kinematics_homing(AxisMask& axisMask) { + return false; // kinematics does not do the homing for catesian systems + } + // Configuration registration namespace { KinematicsFactory::InstanceBuilder registration("Cartesian"); diff --git a/FluidNC/src/Kinematics/Cartesian.h b/FluidNC/src/Kinematics/Cartesian.h index 50476241a..6c4b24c1b 100644 --- a/FluidNC/src/Kinematics/Cartesian.h +++ b/FluidNC/src/Kinematics/Cartesian.h @@ -16,22 +16,33 @@ namespace Kinematics { public: Cartesian() = default; - Cartesian(const Cartesian&) = delete; - Cartesian(Cartesian&&) = delete; + Cartesian(const Cartesian&) = delete; + Cartesian(Cartesian&&) = delete; Cartesian& operator=(const Cartesian&) = delete; - Cartesian& operator=(Cartesian&&) = delete; + Cartesian& operator=(Cartesian&&) = delete; // Kinematic Interface + virtual void constrain_jog(float* cartesian, plan_line_data_t* pl_data, float* position) override; + virtual bool invalid_line(float* cartesian) override; + virtual bool invalid_arc(float* target, + plan_line_data_t* pl_data, + float* position, + float center[3], + float radius, + size_t caxes[3], + bool is_clockwise_arc) override; + virtual bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) override; virtual void init() override; virtual void init_position() override; void motors_to_cartesian(float* cartesian, float* motors, int n_axis) override; - void transform_cartesian_to_motors(float* cartesian, float* motors) override; + bool transform_cartesian_to_motors(float* cartesian, float* motors) override; bool canHome(AxisMask axisMask) override; void releaseMotors(AxisMask axisMask, MotorMask motors) override; bool limitReached(AxisMask& axisMask, MotorMask& motors, MotorMask limited) override; + virtual bool kinematics_homing(AxisMask& axisMask) override; // Configuration handlers: void afterParse() override {} diff --git a/FluidNC/src/Kinematics/CoreXY.cpp b/FluidNC/src/Kinematics/CoreXY.cpp index edcddc908..76815c75d 100644 --- a/FluidNC/src/Kinematics/CoreXY.cpp +++ b/FluidNC/src/Kinematics/CoreXY.cpp @@ -132,7 +132,7 @@ namespace Kinematics { /* Kinematic equations */ - void CoreXY::transform_cartesian_to_motors(float* motors, float* cartesian) { + bool CoreXY::transform_cartesian_to_motors(float* motors, float* cartesian) { motors[X_AXIS] = (_x_scaler * cartesian[X_AXIS]) + cartesian[Y_AXIS]; motors[Y_AXIS] = (_x_scaler * cartesian[X_AXIS]) - cartesian[Y_AXIS]; @@ -140,6 +140,7 @@ namespace Kinematics { for (size_t axis = Z_AXIS; axis < n_axis; axis++) { motors[axis] = cartesian[axis]; } + return true; } // Configuration registration diff --git a/FluidNC/src/Kinematics/CoreXY.h b/FluidNC/src/Kinematics/CoreXY.h index 9c5d6c63f..a24071a77 100644 --- a/FluidNC/src/Kinematics/CoreXY.h +++ b/FluidNC/src/Kinematics/CoreXY.h @@ -40,7 +40,7 @@ namespace Kinematics { virtual void group(Configuration::HandlerBase& handler) override; void afterParse() override {} - void transform_cartesian_to_motors(float* motors, float* cartesian) override; + bool transform_cartesian_to_motors(float* motors, float* cartesian) override; // Name of the configurable. Must match the name registered in the cpp file. virtual const char* name() const override { return "CoreXY"; } diff --git a/FluidNC/src/Kinematics/Kinematics.cpp b/FluidNC/src/Kinematics/Kinematics.cpp index 1a186f7d0..83249e4f3 100644 --- a/FluidNC/src/Kinematics/Kinematics.cpp +++ b/FluidNC/src/Kinematics/Kinematics.cpp @@ -8,6 +8,22 @@ #include "Cartesian.h" namespace Kinematics { + void Kinematics::constrain_jog(float* target, plan_line_data_t* pl_data, float* position) { + Assert(_system != nullptr, "No kinematic system"); + return _system->constrain_jog(target, pl_data, position); + } + + bool Kinematics::invalid_line(float* target) { + Assert(_system != nullptr, "No kinematic system"); + return _system->invalid_line(target); + } + + bool Kinematics::invalid_arc( + float* target, plan_line_data_t* pl_data, float* position, float center[3], float radius, size_t caxes[3], bool is_clockwise_arc) { + Assert(_system != nullptr, "No kinematic system"); + return _system->invalid_arc(target, pl_data, position, center, radius, caxes, is_clockwise_arc); + } + bool Kinematics::cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) { Assert(_system != nullptr, "No kinematic system"); return _system->cartesian_to_motors(target, pl_data, position); @@ -23,6 +39,11 @@ namespace Kinematics { return _system->canHome(axisMask); } + bool Kinematics::kinematics_homing(AxisMask axisMask) { + Assert(_system != nullptr, "No kinematic system"); + return _system->kinematics_homing(axisMask); + } + void Kinematics::releaseMotors(AxisMask axisMask, MotorMask motors) { Assert(_system != nullptr, "No kinematic system"); _system->releaseMotors(axisMask, motors); @@ -33,7 +54,7 @@ namespace Kinematics { return _system->limitReached(axisMask, motors, limited); } - void Kinematics::transform_cartesian_to_motors(float* motors, float* cartesian) { + bool Kinematics::transform_cartesian_to_motors(float* motors, float* cartesian) { Assert(_system != nullptr, "No kinematics system."); return _system->transform_cartesian_to_motors(motors, cartesian); } diff --git a/FluidNC/src/Kinematics/Kinematics.h b/FluidNC/src/Kinematics/Kinematics.h index e8ea30352..7f57b3f5b 100644 --- a/FluidNC/src/Kinematics/Kinematics.h +++ b/FluidNC/src/Kinematics/Kinematics.h @@ -46,9 +46,15 @@ namespace Kinematics { bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position); void motors_to_cartesian(float* cartesian, float* motors, int n_axis); - void transform_cartesian_to_motors(float* motors, float* cartesian); + bool transform_cartesian_to_motors(float* motors, float* cartesian); + + void constrain_jog(float* target, plan_line_data_t* pl_data, float* position); + bool invalid_line(float* target); + bool invalid_arc( + float* target, plan_line_data_t* pl_data, float* position, float center[3], float radius, size_t caxes[3], bool is_clockwise_arc); bool canHome(AxisMask axisMask); + bool kinematics_homing(AxisMask axisMask); void releaseMotors(AxisMask axisMask, MotorMask motors); bool limitReached(AxisMask& axisMask, MotorMask& motors, MotorMask limited); @@ -68,14 +74,23 @@ namespace Kinematics { // Kinematic system interface. virtual bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) = 0; virtual void init() = 0; - virtual void init_position() = 0; // used to set the machine position at init + virtual void init_position() = 0; // used to set the machine position at init + + virtual void constrain_jog(float* cartesian, plan_line_data_t* pl_data, float* position) {} + virtual bool invalid_line(float* cartesian) { return false; } + virtual bool invalid_arc( + float* target, plan_line_data_t* pl_data, float* position, float center[3], float radius, size_t caxes[3], bool is_clockwise_arc) { + return false; + } + virtual void motors_to_cartesian(float* cartesian, float* motors, int n_axis) = 0; - virtual void transform_cartesian_to_motors(float* motors, float* cartesian) = 0; + virtual bool transform_cartesian_to_motors(float* motors, float* cartesian) = 0; virtual bool canHome(AxisMask axisMask) { return false; } virtual void releaseMotors(AxisMask axisMask, MotorMask motors) {} virtual bool limitReached(AxisMask& axisMask, MotorMask& motors, MotorMask limited) { return false; } + virtual bool kinematics_homing(AxisMask& axisMask) { return false; } // Configuration interface. void afterParse() override {} diff --git a/FluidNC/src/Kinematics/ParallelDelta.cpp b/FluidNC/src/Kinematics/ParallelDelta.cpp new file mode 100644 index 000000000..f365d7942 --- /dev/null +++ b/FluidNC/src/Kinematics/ParallelDelta.cpp @@ -0,0 +1,371 @@ +#include "ParallelDelta.h" + +#include "../Machine/MachineConfig.h" +#include "../Limits.h" // ambiguousLimit() +#include "../Machine/Homing.h" + +#include "../Protocol.h" // protocol_execute_realtime + +#include + +/* + ==================== How it Works ==================================== + On a delta machine, Grbl axis units are in radians + The kinematics converts the cartesian moves in gcode into + the radians to move the arms. The Grbl motion planner never sees + the actual cartesian values. + + To make the moves straight and smooth on a delta, the cartesian moves + are broken into small segments where the non linearity will not be noticed. + This is similar to how Grbl draws arcs. + + For mpos reporting, the motor position in steps is proportional to arm angles + in radians, which is then converted to cartesian via the forward kinematics + transform. Arm angle 0 means horizontal. + + Positive angles are below horizontal. + + The machine's Z zero point in the kinematics is parallel to the arm axes. + The offset of the Z distance from the arm axes to the end effector joints + at arm angle zero will be printed at startup on the serial port. + + Feedrate in gcode is in the cartesian units. This must be converted to the + angles. This is done by calculating the segment move distance and the angle + move distance and applying that ration to the feedrate. + + FYI: http://forums.trossenrobotics.com/tutorials/introduction-129/delta-robot-kinematics-3276/ + Better: http://hypertriangle.com/~alex/delta-robot-tutorial/ + + +Default configuration + +kinematics: + ParallelDelta: + + TODO + - Constrain the geometry values to realistic values. + - Implement $MI for dynamixel motors. + +*/ + +namespace Kinematics { + + // trigonometric constants to speed up calculations + const float sqrt3 = 1.732050807; + const float dtr = M_PI / (float)180.0; // degrees to radians + const float sin120 = sqrt3 / 2.0; + const float cos120 = -0.5; + const float tan60 = sqrt3; + const float sin30 = 0.5; + const float tan30 = 1.0 / sqrt3; + + // the geometry of the delta + float rf; // radius of the fixed side (length of motor cranks) + float re; // radius of end effector side (length of linkages) + float f; // sized of fixed side triangel + float e; // size of end effector side triangle + + static float last_angle[MAX_N_AXIS] = { 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs + static float last_cartesian[MAX_N_AXIS] = { 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs + + void ParallelDelta::group(Configuration::HandlerBase& handler) { + handler.item("crank_mm", rf, 50.0, 500.0); + handler.item("base_triangle_mm", f, 20.0, 500.0); + handler.item("linkage_mm", re, 20.0, 500.0); + handler.item("end_effector_triangle_mm", e, 20.0, 500.0); + handler.item("kinematic_segment_len_mm", _kinematic_segment_len_mm, 0.05, 20.0); // + handler.item("homing_mpos_radians", _homing_mpos); + handler.item("soft_limits", _softLimits); + handler.item("max_z_mm", _max_z, -10000.0, 0.0); // + handler.item("use_servos", _use_servos); + } + + void ParallelDelta::init() { + // print a startup message to show the kinematics are enabled. Print the offset for reference + log_info("Kinematic system:" << name() << " soft_limits:" << _softLimits); + + auto axes = config->_axes; + auto n_axis = config->_axes->_numberAxis; + + // warn about axissofy limits + for (int axis = 0; axis < n_axis; axis++) { + if (axes->_axis[axis]->_softLimits) { + log_warn(" All soft_limits configured in axes should be false"); + break; + } + } + + init_position(); + } + + void ParallelDelta::init_position() { + float angles[MAX_N_AXIS] = { 0.0, 0.0, 0.0 }; + float cartesian[MAX_N_AXIS] = { 0.0, 0.0, 0.0 }; + // Calculate the Z offset at the arm zero angles ... + // Z offset is the z distance from the motor axes to the end effector axes at zero angle + motors_to_cartesian(cartesian, angles, 3); // Sets the cartesian values + log_info(" Z Offset:" << cartesian[Z_AXIS]); + } + + bool ParallelDelta::invalid_line(float* cartesian) { + if (!_softLimits) + return false; + + float motors[MAX_N_AXIS] = { 0.0, 0.0, 0.0 }; + + if (!transform_cartesian_to_motors(motors, cartesian)) { + limit_error(); + return true; + } + + return false; + } + + // TO DO. This is not supported yet. Other levels of protection will prevent "damage" + bool ParallelDelta::invalid_arc( + float* target, plan_line_data_t* pl_data, float* position, float center[3], float radius, size_t caxes[3], bool is_clockwise_arc) { + return false; + } + + // copied from Cartesian . Needs to be optimized for parallel delta. + void ParallelDelta::constrain_jog(float* target, plan_line_data_t* pl_data, float* position) { + // log_debug("Jog Test: from(" << position[X_AXIS] << ")" + // << " to(" << target[X_AXIS] << ")"); + if (!_softLimits) + return; + + float motors[MAX_N_AXIS] = { 0.0, 0.0, 0.0 }; + + // Temp fix + // If the target is reachable do nothing + if (transform_cartesian_to_motors(motors, target)) { + return; + } else { + log_warn("Kinematics soft limit jog rejection"); + copyAxes(target, position); + } + + // TO DO better idea + // loop back from the target in increments of kinematic_segment_len_mm unitl the position is valid. + // constrain to that target. + } + + bool ParallelDelta::cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) { + float dx, dy, dz; // distances in each cartesian axis + float motor_angles[3]; + + float seg_target[3]; // The target of the current segment + float feed_rate = pl_data->feed_rate; // save original feed rate + bool show_error = true; // shows error once + + bool calc_ok = true; + + if (target[Z_AXIS] > _max_z) { + log_debug("Kinematics error. Target:" << target[Z_AXIS] << " exceeds max_z:" << _max_z); + return false; + } + + //log_debug("Target (" << target[0] << "," << target[1] << "," << target[2]); + + calc_ok = transform_cartesian_to_motors(last_angle, position); + if (!calc_ok) { + log_warn("Kinematics error. Start position error (" << position[0] << "," << position[1] << "," << position[2] << ")"); + return false; + } + + // Check the destination to see if it is in work area + calc_ok = transform_cartesian_to_motors(motor_angles, target); + if (!calc_ok) { + log_warn("Kinematics error. Target unreachable (" << target[0] << "," << target[1] << "," << target[2] << ")"); + return false; + } + + position[X_AXIS] += gc_state.coord_offset[X_AXIS]; + position[Y_AXIS] += gc_state.coord_offset[Y_AXIS]; + position[Z_AXIS] += gc_state.coord_offset[Z_AXIS]; + + // calculate cartesian move distance for each axis + dx = target[X_AXIS] - position[X_AXIS]; + dy = target[Y_AXIS] - position[Y_AXIS]; + dz = target[Z_AXIS] - position[Z_AXIS]; + float dist = sqrt((dx * dx) + (dy * dy) + (dz * dz)); + + // determine the number of segments we need ... round up so there is at least 1 (except when dist is 0) + uint32_t segment_count = ceil(dist / _kinematic_segment_len_mm); + + float segment_dist = dist / ((float)segment_count); // distance of each segment...will be used for feedrate conversion + + for (uint32_t segment = 1; segment <= segment_count; segment++) { + if (sys.abort) { + return true; + } + //log_debug("Segment:" << segment << " of " << segment_count); + // determine this segment's target + seg_target[X_AXIS] = position[X_AXIS] + (dx / float(segment_count) * segment); + seg_target[Y_AXIS] = position[Y_AXIS] + (dy / float(segment_count) * segment); + seg_target[Z_AXIS] = position[Z_AXIS] + (dz / float(segment_count) * segment); + + //log_debug("Segment target (" << seg_target[0] << "," << seg_target[1] << "," << seg_target[2] << ")"); + + // calculate the delta motor angles + bool calc_ok = transform_cartesian_to_motors(motor_angles, seg_target); + + if (!calc_ok) { + if (show_error) { + log_error("Kinematic error motors (" << motor_angles[0] << "," << motor_angles[1] << "," << motor_angles[2] << ")"); + show_error = false; + } + return false; + } + if (pl_data->motion.rapidMotion) { + pl_data->feed_rate = feed_rate; + } else { + float delta_distance = three_axis_dist(motor_angles, last_angle); + pl_data->feed_rate = (feed_rate * delta_distance / segment_dist); + } + + // mc_line() returns false if a jog is cancelled. + // In that case we stop sending segments to the planner. + if (!mc_move_motors(motor_angles, pl_data)) { + return false; + } + + // save angles for next distance calc + // This is after mc_line() so that we do not update + // last_angle if the segment was discarded. + memcpy(last_angle, motor_angles, sizeof(motor_angles)); + } + return true; + } + + void ParallelDelta::motors_to_cartesian(float* cartesian, float* motors, int n_axis) { + //log_debug("motors_to_cartesian motors: (" << motors[0] << "," << motors[1] << "," << motors[2] << ")"); + //log_info("motors_to_cartesian rf:" << rf << " re:" << re << " f:" << f << " e:" << e); + + float t = (f - e) * tan30 / 2; + + float y1 = -(t + rf * cos(motors[0])); + float z1 = -rf * sin(motors[0]); + + float y2 = (t + rf * cos(motors[1])) * sin30; + float x2 = y2 * tan60; + float z2 = -rf * sin(motors[1]); + + float y3 = (t + rf * cos(motors[2])) * sin30; + float x3 = -y3 * tan60; + float z3 = -rf * sin(motors[2]); + + float dnm = (y2 - y1) * x3 - (y3 - y1) * x2; + + float w1 = y1 * y1 + z1 * z1; + float w2 = x2 * x2 + y2 * y2 + z2 * z2; + float w3 = x3 * x3 + y3 * y3 + z3 * z3; + + // x = (a1*z + b1)/dnm + float a1 = (z2 - z1) * (y3 - y1) - (z3 - z1) * (y2 - y1); + float b1 = -((w2 - w1) * (y3 - y1) - (w3 - w1) * (y2 - y1)) / 2.0; + + // y = (a2*z + b2)/dnm; + float a2 = -(z2 - z1) * x3 + (z3 - z1) * x2; + float b2 = ((w2 - w1) * x3 - (w3 - w1) * x2) / 2.0; + + // a*z^2 + b*z + c = 0 + float a = a1 * a1 + a2 * a2 + dnm * dnm; + float b = 2 * (a1 * b1 + a2 * (b2 - y1 * dnm) - z1 * dnm * dnm); + float c = (b2 - y1 * dnm) * (b2 - y1 * dnm) + b1 * b1 + dnm * dnm * (z1 * z1 - re * re); + + // discriminant + float d = b * b - (float)4.0 * a * c; + if (d < 0) { + log_warn("Forward Kinematics Error"); + return; + } + cartesian[Z_AXIS] = -(float)0.5 * (b + sqrt(d)) / a; + cartesian[X_AXIS] = (a1 * cartesian[Z_AXIS] + b1) / dnm; + cartesian[Y_AXIS] = (a2 * cartesian[Z_AXIS] + b2) / dnm; + } + + bool ParallelDelta::kinematics_homing(AxisMask& axisMask) { + // only servos use custom homing. Steppers use limit switches + if (!_use_servos) + false; + + auto axes = config->_axes; + auto n_axis = axes->_numberAxis; + + config->_axes->set_disable(false); + + // TODO deal with non kinematic axes above Z + for (int axis = 0; axis < 3; axis++) { + //set_motor_steps(axis, mpos_to_steps(axes->_axis[axis]->_homing->_mpos, axis)); + int32_t steps = mpos_to_steps(_homing_mpos, axis); + set_motor_steps(axis, steps); + } + protocol_disable_steppers(); + return true; // signal main code that this handled all homing + } + + // helper functions, calculates angle theta1 (for YZ-pane) + bool ParallelDelta::delta_calcAngleYZ(float x0, float y0, float z0, float& theta) { + float y1 = -0.5 * 0.57735 * f; // f/2 * tg 30 + y0 -= 0.5 * 0.57735 * e; // shift center to edge + // z = a + b*y + float a = (x0 * x0 + y0 * y0 + z0 * z0 + rf * rf - re * re - y1 * y1) / (2 * z0); + float b = (y1 - y0) / z0; + // discriminant + float d = -(a + b * y1) * (a + b * y1) + rf * (b * b * rf + rf); + if (d < 0) { + //log_warn("Kinematics: Target unreachable"); + return false; + } // non-existing point + float yj = (y1 - a * b - sqrt(d)) / (b * b + 1); // choosing outer point + float zj = a + b * yj; + + theta = atan(-zj / (y1 - yj)) + ((yj > y1) ? M_PI : 0.0); + + return true; + } + + void ParallelDelta::releaseMotors(AxisMask axisMask, MotorMask motors) {} + + bool ParallelDelta::transform_cartesian_to_motors(float* motors, float* cartesian) { + motors[0] = motors[1] = motors[2] = 0; + bool calc_ok = false; + + if (cartesian[Z_AXIS] > _max_z) { + log_debug("Kinematics transform error. Target:" << cartesian[Z_AXIS] << " exceeds max_z:" << _max_z); + return false; + } + + calc_ok = delta_calcAngleYZ(cartesian[X_AXIS], cartesian[Y_AXIS], cartesian[Z_AXIS], motors[0]); + if (!calc_ok) { + return calc_ok; + } + + calc_ok = delta_calcAngleYZ(cartesian[X_AXIS] * cos120 + cartesian[Y_AXIS] * sin120, + cartesian[Y_AXIS] * cos120 - cartesian[X_AXIS] * sin120, + cartesian[Z_AXIS], + motors[1]); // rotate coords to +120 deg + if (!calc_ok) { + return calc_ok; + } + + calc_ok = delta_calcAngleYZ(cartesian[X_AXIS] * cos120 - cartesian[Y_AXIS] * sin120, + cartesian[Y_AXIS] * cos120 + cartesian[X_AXIS] * sin120, + cartesian[Z_AXIS], + motors[2]); // rotate coords to -120 deg + + return calc_ok; + } + + // Determine the unit distance between (2) 3D points + float ParallelDelta::three_axis_dist(float* point1, float* point2) { + return sqrt(((point1[0] - point2[0]) * (point1[0] - point2[0])) + ((point1[1] - point2[1]) * (point1[1] - point2[1])) + + ((point1[2] - point2[2]) * (point1[2] - point2[2]))); + } + + // Configuration registration + namespace { + KinematicsFactory::InstanceBuilder registration("parallel_delta"); + } +} diff --git a/FluidNC/src/Kinematics/ParallelDelta.h b/FluidNC/src/Kinematics/ParallelDelta.h new file mode 100644 index 000000000..fc990c2c4 --- /dev/null +++ b/FluidNC/src/Kinematics/ParallelDelta.h @@ -0,0 +1,83 @@ +// Copyright (c) 2021 - Bart Dring +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#pragma once + +/* + + This implements Parallel Delta Kinematics + +*/ + +#include "Kinematics.h" +#include "Cartesian.h" + +// M_PI is not defined in standard C/C++ but some compilers +// support it anyway. The following suppresses Intellisense +// problem reports. +#ifndef M_PI +# define M_PI 3.14159265358979323846 +#endif + +namespace Kinematics { + + class ParallelDelta : public Cartesian { + public: + ParallelDelta() = default; + + ParallelDelta(const ParallelDelta&) = delete; + ParallelDelta(ParallelDelta&&) = delete; + ParallelDelta& operator=(const ParallelDelta&) = delete; + ParallelDelta& operator=(ParallelDelta&&) = delete; + + // Kinematic Interface + virtual void init() override; + virtual void init_position() override; + //bool canHome(AxisMask& axisMask) override; + bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) override; + void motors_to_cartesian(float* cartesian, float* motors, int n_axis) override; + bool transform_cartesian_to_motors(float* motors, float* cartesian) override; + //bool soft_limit_error_exists(float* cartesian) override; + bool kinematics_homing(AxisMask& axisMask) override; + virtual void constrain_jog(float* cartesian, plan_line_data_t* pl_data, float* position) override; + virtual bool invalid_line(float* cartesian) override; + virtual bool invalid_arc(float* target, + plan_line_data_t* pl_data, + float* position, + float center[3], + float radius, + size_t caxes[3], + bool is_clockwise_arc) override; + + void releaseMotors(AxisMask axisMask, MotorMask motors) override; + + // Configuration handlers: + //void validate() const override {} + virtual void group(Configuration::HandlerBase& handler) override; + void afterParse() override {} + + // Name of the configurable. Must match the name registered in the cpp file. + virtual const char* name() const override { return "parallel_delta"; } + + ~ParallelDelta() {} + + private: + // Config items Using geometry names from the published kinematics rather than typical Fluid Style + // To make the math easier to compare with the code + float rf = 70.0; // The length of the crank arm on the motor + float f = 179.437; + float re = 133.50; + float e = 86.603; + + float _kinematic_segment_len_mm = 1.0; // the maximun segment length the move is broken into + bool _softLimits = false; + float _homing_mpos = 0.0; + float _max_z = 0.0; + bool _use_servos = true; // servo use a special homing + + bool delta_calcAngleYZ(float x0, float y0, float z0, float& theta); + float three_axis_dist(float* point1, float* point2); + + protected: + }; +} // namespace Kinematics diff --git a/FluidNC/src/Kinematics/WallPlotter.cpp b/FluidNC/src/Kinematics/WallPlotter.cpp index 88a72a7a9..10e5a09f3 100644 --- a/FluidNC/src/Kinematics/WallPlotter.cpp +++ b/FluidNC/src/Kinematics/WallPlotter.cpp @@ -47,8 +47,9 @@ namespace Kinematics { return false; } - void WallPlotter::transform_cartesian_to_motors(float* cartesian, float* motors) { + bool WallPlotter::transform_cartesian_to_motors(float* cartesian, float* motors) { log_error("WallPlotter::transform_cartesian_to_motors is broken"); + return true; } /* @@ -98,6 +99,9 @@ namespace Kinematics { // Calculate desired cartesian feedrate distance ratio. Same for each seg. for (uint32_t segment = 1; segment <= segment_count; segment++) { + if (sys.abort) { + return true; + } // calculate the cartesian end point of the next segment for (size_t axis = X_AXIS; axis < n_axis; axis++) { cartesian_segment_end[axis] += cartesian_segment_components[axis]; @@ -229,6 +233,10 @@ namespace Kinematics { right_length = hypot_f(right_dx, right_dy); } + bool WallPlotter::kinematics_homing(AxisMask& axisMask) { + return false; // kinematics does not do the homing for catesian systems + } + // Configuration registration namespace { KinematicsFactory::InstanceBuilder registration("WallPlotter"); diff --git a/FluidNC/src/Kinematics/WallPlotter.h b/FluidNC/src/Kinematics/WallPlotter.h index ed558dfe0..f3a4c7518 100644 --- a/FluidNC/src/Kinematics/WallPlotter.h +++ b/FluidNC/src/Kinematics/WallPlotter.h @@ -28,7 +28,8 @@ namespace Kinematics { void init_position() override; bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) override; void motors_to_cartesian(float* cartesian, float* motors, int n_axis) override; - void transform_cartesian_to_motors(float* cartesian, float* motors) override; + bool transform_cartesian_to_motors(float* cartesian, float* motors) override; + bool kinematics_homing(AxisMask& axisMask) override; // Configuration handlers: void validate() override {} diff --git a/FluidNC/src/Limits.cpp b/FluidNC/src/Limits.cpp index b6b1b05b8..1623e30f6 100644 --- a/FluidNC/src/Limits.cpp +++ b/FluidNC/src/Limits.cpp @@ -5,7 +5,7 @@ #include "Limits.h" #include "Machine/MachineConfig.h" -#include "MotionControl.h" // mc_reset +#include "MotionControl.h" // mc_critical #include "System.h" // sys.* #include "Protocol.h" // protocol_execute_realtime #include "Platform.h" // WEAK_LINK @@ -43,10 +43,10 @@ MotorMask limits_get_state() { return Machine::Axes::posLimitMask | Machine::Axes::negLimitMask; } +// Called only from Kinematics canHome() methods, hence from states allowing homing bool ambiguousLimit() { if (Machine::Axes::posLimitMask & Machine::Axes::negLimitMask) { - mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. - rtAlarm = ExecAlarm::HardLimit; + mc_critical(ExecAlarm::HardLimit); return true; } return false; @@ -54,121 +54,34 @@ bool ambiguousLimit() { bool soft_limit = false; -// Constrain the coordinates to stay within the soft limit envelope -void constrainToSoftLimits(float* cartesian) { - auto axes = config->_axes; - auto n_axis = config->_axes->_numberAxis; - - float* current_position = get_mpos(); - MotorMask lim_pin_state = limits_get_state(); - - for (int axis = 0; axis < n_axis; axis++) { - auto axisSetting = axes->_axis[axis]; - // If the axis is moving from the current location and soft limits are on. - if (axisSetting->_softLimits && cartesian[axis] != current_position[axis]) { - // When outside the axis range, only small nudges to clear switches are allowed - if (current_position[axis] < limitsMinPosition(axis) || current_position[axis] > limitsMaxPosition(axis)) { - // only allow a nudge if a switch is active - if (bitnum_is_false(lim_pin_state, Machine::Axes::motor_bit(axis, 0)) && - bitnum_is_false(lim_pin_state, Machine::Axes::motor_bit(axis, 1))) { - cartesian[axis] = current_position[axis]; // cancel the move on this axis - log_debug("Soft limit violation on " << Machine::Axes::_names[axis]); - continue; - } - float jog_dist = cartesian[axis] - current_position[axis]; - - MotorMask axisMotors = Machine::Axes::axes_to_motors(1 << axis); - bool posLimited = bits_are_true(Machine::Axes::posLimitMask, axisMotors); - bool negLimited = bits_are_true(Machine::Axes::negLimitMask, axisMotors); - - // if jog is positive and only the positive switch is active, then kill the move - // if jog is negative and only the negative switch is active, then kill the move - if (posLimited != negLimited) { // XOR, because ambiguous (both) is OK - if ((negLimited && (jog_dist < 0)) || (posLimited && (jog_dist > 0))) { - cartesian[axis] = current_position[axis]; // cancel the move on this axis - log_debug("Jog into active switch blocked on " << Machine::Axes::_names[axis]); - continue; - } - } - - auto nudge_max = axisSetting->_motors[0]->_pulloff; - if (abs(jog_dist) > nudge_max) { - cartesian[axis] = (jog_dist >= 0) ? current_position[axis] + nudge_max : current_position[axis] + nudge_max; - log_debug("Jog amount limited when outside soft limits") - } - continue; - } - - if (cartesian[axis] < limitsMinPosition(axis)) { - cartesian[axis] = limitsMinPosition(axis); - } else if (cartesian[axis] > limitsMaxPosition(axis)) { - cartesian[axis] = limitsMaxPosition(axis); - } else { - continue; - } - log_debug("Jog constrained to axis range"); - } - } -} - // Performs a soft limit check. Called from mcline() only. Assumes the machine has been homed, // the workspace volume is in all negative space, and the system is in normal operation. // NOTE: Used by jogging to limit travel within soft-limit volume. -void limits_soft_check(float* cartesian) { - bool limit_error = false; - - auto axes = config->_axes; - auto n_axis = config->_axes->_numberAxis; - - for (int axis = 0; axis < n_axis; axis++) { - if (axes->_axis[axis]->_softLimits && (cartesian[axis] < limitsMinPosition(axis) || cartesian[axis] > limitsMaxPosition(axis))) { - log_info("Soft limit on " << Machine::Axes::_names[axis] << " target:" << cartesian[axis]); - limit_error = true; - } - } +void limit_error(size_t axis, float coordinate) { + log_info("Soft limit on " << Machine::Axes::_names[axis] << " target:" << coordinate); - if (limit_error) { - soft_limit = true; - // Force feed hold if cycle is active. All buffered blocks are guaranteed to be within - // workspace volume so just come to a controlled stop so position is not lost. When complete - // enter alarm mode. - if (sys.state == State::Cycle) { - protocol_send_event(&feedHoldEvent); - do { - protocol_execute_realtime(); - if (sys.abort) { - return; - } - } while (sys.state != State::Idle); - } - log_debug("Soft limits"); - mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. - rtAlarm = ExecAlarm::SoftLimit; // Indicate soft limit critical event - protocol_execute_realtime(); // Execute to enter critical event loop and system abort - } + limit_error(); } -#ifdef LATER // We need to rethink debouncing -void limitCheckTask(void* pvParameters) { - while (true) { - std::atomic_thread_fence(std::memory_order::memory_order_seq_cst); // read fence for settings - - int evt; - xQueueReceive(limit_sw_queue, &evt, portMAX_DELAY); // block until receive queue - vTaskDelay(config->_softwareDebounceMs / portTICK_PERIOD_MS); // delay a while - auto switch_state = limits_get_state(); - if (switch_state) { - log_debug("Limit Switch State " << to_hex(switch_state)); - mc_reset(); // Initiate system kill. - rtAlarm = ExecAlarm::HardLimit; // Indicate hard limit critical event - } - static UBaseType_t uxHighWaterMark = 0; -# ifdef DEBUG_TASK_STACK - reportTaskStackSize(uxHighWaterMark); -# endif +void limit_error() { + + soft_limit = true; + // Force feed hold if cycle is active. All buffered blocks are guaranteed to be within + // workspace volume so just come to a controlled stop so position is not lost. When complete + // enter alarm mode. + protocol_buffer_synchronize(); + if (sys.state == State::Cycle) { + protocol_send_event(&feedHoldEvent); + do { + protocol_execute_realtime(); + if (sys.abort) { + return; + } + } while (sys.state != State::Idle); } + + mc_critical(ExecAlarm::SoftLimit); } -#endif float limitsMaxPosition(size_t axis) { auto axisConfig = config->_axes->_axis[axis]; diff --git a/FluidNC/src/Limits.h b/FluidNC/src/Limits.h index e24e85bf2..03d81d066 100644 --- a/FluidNC/src/Limits.h +++ b/FluidNC/src/Limits.h @@ -4,7 +4,7 @@ #pragma once -#include "System.h" // AxisMask +#include "System.h" #include @@ -16,11 +16,8 @@ void limits_init(); // Returns limit state MotorMask limits_get_state(); -// Check for soft limit violations -void limits_soft_check(float* cartesian); - -// Constrain the coordinates to stay within the soft limit envelope -void constrainToSoftLimits(float* cartesian); +void limit_error(); +void limit_error(size_t axis, float cordinate); float limitsMaxPosition(size_t axis); float limitsMinPosition(size_t axis); diff --git a/FluidNC/src/Logging.cpp b/FluidNC/src/Logging.cpp index 39540896e..593c3d17c 100644 --- a/FluidNC/src/Logging.cpp +++ b/FluidNC/src/Logging.cpp @@ -6,15 +6,22 @@ #include "Serial.h" #include "SettingsDefinitions.h" +EnumItem messageLevels2[] = { + { MsgLevelNone, "None" }, { MsgLevelError, "Error" }, { MsgLevelWarning, "Warn" }, + { MsgLevelInfo, "Info" }, { MsgLevelDebug, "Debug" }, { MsgLevelVerbose, "Verbose" }, +}; + bool atMsgLevel(MsgLevel level) { return message_level == nullptr || message_level->get() >= level; } -LogStream::LogStream(Channel& channel, const char* name) : _channel(channel) { +LogStream::LogStream(Channel& channel, MsgLevel level, const char* name) : _channel(channel), _level(level) { _line = new std::string(); print(name); } -LogStream::LogStream(const char* name) : LogStream(allChannels, name) {} + +LogStream::LogStream(Channel& channel, const char* name) : LogStream(channel, MsgLevelNone, name) {} +LogStream::LogStream(MsgLevel level, const char* name) : LogStream(allChannels, level, name) {} size_t LogStream::write(uint8_t c) { *_line += (char)c; @@ -25,5 +32,5 @@ LogStream::~LogStream() { if ((*_line).length() && (*_line)[0] == '[') { *_line += ']'; } - send_line(_channel, _line); + send_line(_channel, _level, _line); } diff --git a/FluidNC/src/Logging.h b/FluidNC/src/Logging.h index 256cfe90f..53b28061f 100644 --- a/FluidNC/src/Logging.h +++ b/FluidNC/src/Logging.h @@ -4,6 +4,7 @@ #pragma once #include +#include "EnumItem.h" class Channel; @@ -16,6 +17,8 @@ enum MsgLevel { MsgLevelVerbose = 5, }; +extern EnumItem messageLevels2[]; + // How to use logging? Well, the basics are pretty simple: // // - The syntax is like standard iostream's. @@ -34,13 +37,15 @@ enum MsgLevel { class LogStream : public Print { public: LogStream(Channel& channel, const char* name); - LogStream(const char* name); + LogStream(Channel& channel, MsgLevel level, const char* name); + LogStream(MsgLevel level, const char* name); size_t write(uint8_t c) override; ~LogStream(); private: Channel& _channel; std::string* _line; + MsgLevel _level; }; extern bool atMsgLevel(MsgLevel level); @@ -50,21 +55,21 @@ extern bool atMsgLevel(MsgLevel level); // Note: these '{'..'}' scopes are here for a reason: the destructor should flush. // #define log_bare(prefix, x) { LogStream ss(prefix); ss << x; } -#define log_msg(x) { LogStream ss("[MSG: "); ss << x; } -#define log_verbose(x) if (atMsgLevel(MsgLevelVerbose)) { LogStream ss("[MSG:VRB: "); ss << x; } -#define log_debug(x) if (atMsgLevel(MsgLevelDebug)) { LogStream ss("[MSG:DBG: "); ss << x; } -#define log_info(x) if (atMsgLevel(MsgLevelInfo)) { LogStream ss("[MSG:INFO: "); ss << x; } -#define log_warn(x) if (atMsgLevel(MsgLevelWarning)) { LogStream ss("[MSG:WARN: "); ss << x; } -#define log_error(x) if (atMsgLevel(MsgLevelError)) { LogStream ss("[MSG:ERR: "); ss << x; } -#define log_fatal(x) { LogStream ss("[MSG:FATAL: "); ss << x; Assert(false, "A fatal error occurred."); } - -#define log_msg_to(out, x) { LogStream ss(out, "[MSG: "); ss << x; } -#define log_verbose_to(out, x) if (atMsgLevel(MsgLevelVerbose)) { LogStream ss(out, "[MSG:VRB: "); ss << x; } -#define log_debug_to(out, x) if (atMsgLevel(MsgLevelDebug)) { LogStream ss(out, "[MSG:DBG: "); ss << x; } -#define log_info_to(out, x) if (atMsgLevel(MsgLevelInfo)) { LogStream ss(out, "[MSG:INFO: "); ss << x; } -#define log_warn_to(out, x) if (atMsgLevel(MsgLevelWarning)) { LogStream ss(out, "[MSG:WARN: "); ss << x; } -#define log_error_to(out, x) if (atMsgLevel(MsgLevelError)) { LogStream ss(out, "[MSG:ERR: "); ss << x; } -#define log_fatal_to(out, x) { LogStream ss(out, "[MSG:FATAL: "); ss << x; Assert(false, "A fatal error occurred."); } +#define log_msg(x) { LogStream ss(MsgLevelNone, "[MSG:"); ss << x; } +#define log_verbose(x) if (atMsgLevel(MsgLevelVerbose)) { LogStream ss(MsgLevelVerbose, "[MSG:VRB: "); ss << x; } +#define log_debug(x) if (atMsgLevel(MsgLevelDebug)) { LogStream ss(MsgLevelDebug, "[MSG:DBG: "); ss << x; } +#define log_info(x) if (atMsgLevel(MsgLevelInfo)) { LogStream ss(MsgLevelInfo, "[MSG:INFO: "); ss << x; } +#define log_warn(x) if (atMsgLevel(MsgLevelWarning)) { LogStream ss(MsgLevelWarning, "[MSG:WARN: "); ss << x; } +#define log_error(x) if (atMsgLevel(MsgLevelError)) { LogStream ss(MsgLevelError, "[MSG:ERR: "); ss << x; } +#define log_fatal(x) { LogStream ss(MsgLevelNone, "[MSG:FATAL: "); ss << x; Assert(false, "A fatal error occurred."); } + +#define log_msg_to(out, x) { LogStream ss(out, MsgLevelNone, "[MSG:"); ss << x; } +#define log_verbose_to(out, x) if (atMsgLevel(MsgLevelVerbose)) { LogStream ss(out, MsgLevelVerbose, "[MSG:VRB: "); ss << x; } +#define log_debug_to(out, x) if (atMsgLevel(MsgLevelDebug)) { LogStream ss(out, MsgLevelDebug, "[MSG:DBG: "); ss << x; } +#define log_info_to(out, x) if (atMsgLevel(MsgLevelInfo)) { LogStream ss(out, MsgLevelInfo, "[MSG:INFO: "); ss << x; } +#define log_warn_to(out, x) if (atMsgLevel(MsgLevelWarning)) { LogStream ss(out, MsgLevelWarning, "[MSG:WARN: "); ss << x; } +#define log_error_to(out, x) if (atMsgLevel(MsgLevelError)) { LogStream ss(out, MsgLevelError, "[MSG:ERR: "); ss << x; } +#define log_fatal_to(out, x) { LogStream ss(out, MsgLevelNone, "[MSG:FATAL: "); ss << x; Assert(false, "A fatal error occurred."); } // GET_MACRO is a preprocessor trick to let log_to() behave differently // with 2 arguments vs 3. The 2 argument case is super efficient @@ -76,5 +81,5 @@ extern bool atMsgLevel(MsgLevel level); #define GET_MACRO(_1,_2,_3, NAME, ...) NAME #define log_to(...) GET_MACRO(__VA_ARGS__, log_to3, log_to2)(__VA_ARGS__) -#define log_to2(out, prefix) send_line(out, prefix) -#define log_to3(out, prefix, x) { LogStream ss(out, prefix); ss << x; } +#define log_to2(out, prefix) send_line(out, MsgLevelNone, prefix) +#define log_to3(out, prefix, x) { LogStream ss(out, MsgLevelNone, prefix); ss << x; } diff --git a/FluidNC/src/Machine/Axes.cpp b/FluidNC/src/Machine/Axes.cpp index 4e94efd7b..ae7dc8121 100644 --- a/FluidNC/src/Machine/Axes.cpp +++ b/FluidNC/src/Machine/Axes.cpp @@ -13,10 +13,11 @@ EnumItem axisType[] = { { 0, "X" }, { 1, "Y" }, { 2, "Z" }, { 3, "A" }, { 4, "B" namespace Machine { MotorMask Axes::posLimitMask = 0; MotorMask Axes::negLimitMask = 0; - MotorMask Axes::homingMask = 0; MotorMask Axes::limitMask = 0; MotorMask Axes::motorMask = 0; + AxisMask Axes::homingMask = 0; + Axes::Axes() : _axis() { for (int i = 0; i < MAX_N_AXIS; ++i) { _axis[i] = nullptr; @@ -64,6 +65,11 @@ namespace Machine { } _sharedStepperDisable.synchronousWrite(disable); + + if (!disable && config->_stepping->_disableDelayUsecs) { // wait for the enable delay + log_debug("enable delay:" << config->_stepping->_disableDelayUsecs); + delay_us(config->_stepping->_disableDelayUsecs); + } } // Put the motors in the given axes into homing mode, returning a diff --git a/FluidNC/src/Machine/Axes.h b/FluidNC/src/Machine/Axes.h index dfbd7005f..90bff23de 100644 --- a/FluidNC/src/Machine/Axes.h +++ b/FluidNC/src/Machine/Axes.h @@ -24,19 +24,20 @@ namespace Machine { // Bitmasks to collect information about axes that have limits and homing static MotorMask posLimitMask; static MotorMask negLimitMask; - static MotorMask homingMask; static MotorMask limitMask; static MotorMask motorMask; + static AxisMask homingMask; + + Pin _sharedStepperDisable; + Pin _sharedStepperReset; + inline char axisName(int index) { return index < MAX_N_AXIS ? _names[index] : '?'; } // returns axis letter static inline size_t motor_bit(size_t axis, size_t motor) { return motor ? axis + 16 : axis; } static inline AxisMask motors_to_axes(MotorMask motors) { return (motors & 0xffff) | (motors >> 16); } static inline MotorMask axes_to_motors(AxisMask axes) { return axes | (axes << 16); } - Pin _sharedStepperDisable; - Pin _sharedStepperReset; - int _numberAxis = 0; Axis* _axis[MAX_N_AXIS]; @@ -72,7 +73,8 @@ namespace Machine { void config_motors(); std::string maskToNames(AxisMask mask); - bool namesToMask(const char* names, AxisMask& mask); + + bool namesToMask(const char* names, AxisMask& mask); std::string motorMaskToNames(MotorMask mask); diff --git a/FluidNC/src/Machine/Axis.cpp b/FluidNC/src/Machine/Axis.cpp index 3d0be46ce..a87081fc5 100644 --- a/FluidNC/src/Machine/Axis.cpp +++ b/FluidNC/src/Machine/Axis.cpp @@ -29,8 +29,7 @@ namespace Machine { auto maxRate = config->_stepping->maxPulsesPerSec(); Assert(stepRate <= maxRate, "Stepping rate %d steps/sec exceeds the maximum rate %d", stepRate, maxRate); if (_homing == nullptr) { - _homing = new Homing(); - _homing->_cycle = 0; + _homing = new Homing(); } if (_motors[0] == nullptr) { _motors[0] = new Machine::Motor(_axis, 0); @@ -45,7 +44,7 @@ namespace Machine { m->init(); } } - if (_homing) { + if (_homing && _homing->_cycle != 0) { _homing->init(); set_bitnum(Axes::homingMask, _axis); } diff --git a/FluidNC/src/Machine/EventPin.cpp b/FluidNC/src/Machine/EventPin.cpp index bc9baabbe..1ffc251ff 100644 --- a/FluidNC/src/Machine/EventPin.cpp +++ b/FluidNC/src/Machine/EventPin.cpp @@ -1,36 +1,15 @@ #include "EventPin.h" +#include "src/Report.h" -#include "src/Report.h" // addPinReport -#include "src/Protocol.h" // event_queue -#include "src/System.h" // sys +#include "src/Protocol.h" // protocol_send_event -#include "Driver/fluidnc_gpio.h" +EventPin::EventPin(Event* event, const char* legend) : _event(event), _legend(legend) {} -namespace Machine { - EventPin::EventPin(Event* event, const char* legend, Pin* pin) : _event(event), _legend(legend), _pin(pin) {} - bool EventPin::get() { return _pin->read(); } - - void EventPin::gpioAction(int gpio_num, void* arg, bool active) { - EventPin* obj = static_cast(arg); - // protocol_send_event(obj, obj); - obj->update(active); - if (active) { - protocol_send_event(obj->_event, obj); - } - } - - void EventPin::init() { - if (_pin->undefined()) { - return; - } - - _pin->report(_legend); - - auto attr = Pin::Attr::Input; - _pin->setAttr(attr); - _gpio = _pin->getNative(Pin::Capabilities::Input); - gpio_set_action(_gpio, gpioAction, (void*)this, _pin->getAttr().has(Pin::Attr::ActiveLow)); +void EventPin::trigger(bool active) { + update(active); + log_debug(_legend << " " << active); + if (active) { + protocol_send_event(_event, this); } - - EventPin::~EventPin() { gpio_clear_action(_gpio); } -}; + report_recompute_pin_string(); +} diff --git a/FluidNC/src/Machine/EventPin.h b/FluidNC/src/Machine/EventPin.h index 709237bb9..9faa4247a 100644 --- a/FluidNC/src/Machine/EventPin.h +++ b/FluidNC/src/Machine/EventPin.h @@ -1,36 +1,20 @@ #pragma once -#include "src/Pin.h" #include "src/Event.h" -#include "src/Config.h" +#include -namespace Machine { - class EventPin { - protected: - static void gpioAction(int, void*, bool); +class EventPin { +protected: + Event* _event = nullptr; // Subordinate event that is called conditionally - Event* _event = nullptr; // Subordinate event that is called conditionally +public: + std::string _legend; // The name that appears in init() messages and the name of the configuration item - pinnum_t _gpio; + EventPin(Event* event, const char* legend); - static bool inactive(EventPin* pin); + virtual void update(bool state) {}; - public: - std::string _legend; // The name that appears in init() messages and the name of the configuration item + void trigger(bool active); - EventPin(Event* event, const char* legend, Pin* pin); - - // This is a pointer instead of a reference because the derived classes - // like ControlPin and LimitPin "own" the actual Pin object. That is - // necessary because those objects are configurable and must stay - // within their class for later operations on the configuration tree. - Pin* _pin = nullptr; - - void init(); - bool get(); - - virtual void update(bool state) {}; - - ~EventPin(); - }; + ~EventPin() {} }; diff --git a/FluidNC/src/Machine/Homing.cpp b/FluidNC/src/Machine/Homing.cpp index d4e00ec4e..6f0fa302a 100644 --- a/FluidNC/src/Machine/Homing.cpp +++ b/FluidNC/src/Machine/Homing.cpp @@ -1,10 +1,9 @@ #include "Homing.h" -#include "../MotionControl.h" // mc_reset -#include "../System.h" // sys.* -#include "../Stepper.h" // st_wake -#include "../Protocol.h" // protocol_handle_events -#include "../Limits.h" // ambiguousLimit +#include "../System.h" // sys.* +#include "../Stepper.h" // st_wake +#include "../Protocol.h" // protocol_handle_events +#include "../Limits.h" // ambiguousLimit #include "../Machine/Axes.h" #include "../Machine/MachineConfig.h" // config @@ -41,6 +40,28 @@ namespace Machine { std::queue Homing::_remainingCycles; uint32_t Homing::_settling_ms; + AxisMask Homing::_unhomed_axes; // Bitmap of axes whose position is unknown + + bool Homing::axis_is_homed(size_t axis) { + return bitnum_is_false(_unhomed_axes, axis); + } + void Homing::set_axis_homed(size_t axis) { + clear_bitnum(_unhomed_axes, axis); + } + void Homing::set_axis_unhomed(size_t axis) { + set_bitnum(_unhomed_axes, axis); + } + void Homing::set_all_axes_unhomed() { + _unhomed_axes = Machine::Axes::homingMask; + } + void Homing::set_all_axes_homed() { + _unhomed_axes = 0; + } + + AxisMask Homing::unhomed_axes() { + return _unhomed_axes; + } + const char* Homing::_phaseNames[] = { "None", "PrePulloff", "FastApproach", "Pulloff0", "SlowApproach", "Pulloff1", "Pulloff2", "CycleDone", }; @@ -50,7 +71,7 @@ namespace Machine { float target[config->_axes->_numberAxis]; axisVector(_phaseAxes, _phaseMotors, _phase, target, rate, _settling_ms); - plan_line_data_t plan_data; + plan_line_data_t plan_data = {}; plan_data.spindle_speed = 0; plan_data.motion = {}; plan_data.motion.systemMotion = 1; @@ -67,7 +88,9 @@ namespace Machine { protocol_send_event(&cycleStartEvent); } - static MotorMask limited() { return Machine::Axes::posLimitMask | Machine::Axes::negLimitMask; } + static MotorMask limited() { + return Machine::Axes::posLimitMask | Machine::Axes::negLimitMask; + } void Homing::cycleStop() { log_debug("CycleStop " << phaseName(_phase)); @@ -320,9 +343,9 @@ namespace Machine { config->_stepping->endLowLatency(); - if (!sys.abort) { // Execute startup scripts after successful homing. - sys.state = State::Idle; // Set to IDLE when complete. - Stepper::go_idle(); // Set steppers to the settings idle state before returning. + if (!sys.abort) { + sys.state = unhomed_axes() ? State::Alarm : State::Idle; + Stepper::go_idle(); // Set steppers to the settings idle state before returning. } } @@ -351,8 +374,8 @@ namespace Machine { } void Homing::fail(ExecAlarm alarm) { - Stepper::reset(); // Stop moving - rtAlarm = alarm; + Stepper::reset(); // Stop moving + send_alarm(alarm); config->_axes->set_homing_mode(_cycleAxes, false); // tell motors homing is done...failed config->_axes->set_disable(config->_stepping->_idleMsecs != 255); } @@ -390,6 +413,7 @@ namespace Machine { // Replace coordinates homed axes with the homing values. for (size_t axis = 0; axis < n_axis; axis++) { if (bitnum_is_true(_cycleAxes, axis)) { + set_axis_homed(axis); mpos[axis] = axes->_axis[axis]->_homing->_mpos; } } @@ -422,6 +446,11 @@ namespace Machine { // cycle. The protocol loop will then respond to events and advance // the homing state machine through its phases. void Homing::run_cycles(AxisMask axisMask) { + // Check to see if the Kinematics takes care of homing. + if (config->_kinematics->kinematics_homing(axisMask)) { + return; + } + if (!config->_kinematics->canHome(axisMask)) { sys.state = State::Alarm; return; diff --git a/FluidNC/src/Machine/Homing.h b/FluidNC/src/Machine/Homing.h index d1a780c22..682e9678a 100644 --- a/FluidNC/src/Machine/Homing.h +++ b/FluidNC/src/Machine/Homing.h @@ -11,6 +11,8 @@ namespace Machine { class Homing : public Configuration::Configurable { + static AxisMask _unhomed_axes; + public: static enum Phase { None = 0, @@ -23,6 +25,14 @@ namespace Machine { CycleDone = 7, } _phase; + static AxisMask unhomed_axes(); + + static void set_axis_homed(size_t axis); + static void set_axis_unhomed(size_t axis); + static bool axis_is_homed(size_t axis); + static void set_all_axes_homed(); + static void set_all_axes_unhomed(); + Homing() = default; static const int AllCycles = 0; // Must be zero. @@ -44,7 +54,7 @@ namespace Machine { // The homing cycles are 1,2,3 etc. 0 means not homed as part of home-all, // but you can still home it manually with e.g. $HA - int _cycle = -1; // what auto-homing cycle does this axis home on? + int _cycle = 0; // what auto-homing cycle does this axis home on? bool _allow_single_axis = true; // Allow use of $H command on this axis bool _positiveDirection = true; float _mpos = 0.0f; // After homing this will be the mpos of the switch location diff --git a/FluidNC/src/Machine/LimitPin.cpp b/FluidNC/src/Machine/LimitPin.cpp index c4a10008b..986ddd808 100644 --- a/FluidNC/src/Machine/LimitPin.cpp +++ b/FluidNC/src/Machine/LimitPin.cpp @@ -2,13 +2,13 @@ #include "src/Machine/Axes.h" #include "src/Machine/MachineConfig.h" // config -#include "src/MotionControl.h" // mc_reset #include "src/Limits.h" #include "src/Protocol.h" // protocol_send_event_from_ISR() namespace Machine { LimitPin::LimitPin(Pin& pin, int axis, int motor, int direction, bool& pHardLimits, bool& pLimited) : - EventPin(&limitEvent, "Limit", &pin), _axis(axis), _motorNum(motor), _value(false), _pHardLimits(pHardLimits), _pLimited(pLimited) { + EventPin(&limitEvent, "Limit"), _axis(axis), _motorNum(motor), _value(false), _pHardLimits(pHardLimits), _pLimited(pLimited), + _pin(&pin) { const char* sDir; // Select one or two bitmask variables to receive the switch data switch (direction) { @@ -44,15 +44,16 @@ namespace Machine { } void LimitPin::init() { - EventPin::init(); if (_pin->undefined()) { return; } + _pin->report(_legend); + _pin->setAttr(Pin::Attr::Input); + _pin->registerEvent(static_cast(this)); update(get()); } void LimitPin::update(bool value) { - log_debug(_legend << " " << value); if (value) { if (Homing::approach() || (sys.state != State::Homing && _pHardLimits)) { _pLimited = value; diff --git a/FluidNC/src/Machine/LimitPin.h b/FluidNC/src/Machine/LimitPin.h index 251ed97c9..75d02e4fd 100644 --- a/FluidNC/src/Machine/LimitPin.h +++ b/FluidNC/src/Machine/LimitPin.h @@ -25,6 +25,8 @@ namespace Machine { volatile uint32_t* _posLimits = nullptr; volatile uint32_t* _negLimits = nullptr; + Pin* _pin; + public: LimitPin(Pin& pin, int axis, int motorNum, int direction, bool& phardLimits, bool& pLimited); @@ -36,6 +38,8 @@ namespace Machine { bool isHard() { return _pHardLimits; } + bool get() { return _pin->read(); } + int _axis; int _motorNum; }; diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index 11b16ee77..c8c458dbc 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -25,6 +25,7 @@ #include #include #include +#include Machine::MachineConfig* config; @@ -41,8 +42,8 @@ namespace Machine { handler.section("uart1", _uarts[1], 1); handler.section("uart2", _uarts[2], 2); - handler.section("uart_channel1", _uart_channels[1]); - handler.section("uart_channel2", _uart_channels[2]); + handler.section("uart_channel1", _uart_channels[1], 1); + handler.section("uart_channel2", _uart_channels[2], 2); handler.section("i2so", _i2so); @@ -65,6 +66,7 @@ namespace Machine { handler.section("user_outputs", _userOutputs); handler.section("oled", _oled); + handler.section("status_outputs", _stat_out); Spindles::SpindleFactory::factory(handler, _spindles); @@ -147,7 +149,7 @@ namespace Machine { } } - char defaultConfig[] = "name: Default (Test Drive)\nboard: None\n"; + const char defaultConfig[] = "name: Default (Test Drive)\nboard: None\n"; bool MachineConfig::load() { bool configOkay; @@ -158,20 +160,20 @@ namespace Machine { log_error("Skipping configuration file due to panic"); configOkay = false; } else { - configOkay = load(config_filename->get()); + configOkay = load_file(config_filename->get()); } if (!configOkay) { log_info("Using default configuration"); - configOkay = load(new StringRange(defaultConfig)); + configOkay = load_yaml(defaultConfig); } return configOkay; } - bool MachineConfig::load(const char* filename) { + bool MachineConfig::load_file(const std::string_view filename) { try { - FileStream file(filename, "r", ""); + FileStream file(std::string { filename }, "r", ""); auto filesize = file.size(); if (filesize <= 0) { @@ -179,27 +181,26 @@ namespace Machine { return false; } - char* buffer = new char[filesize + 1]; + auto buffer = std::make_unique(filesize + 1); buffer[filesize] = '\0'; - auto actual = file.read(buffer, filesize); + auto actual = file.read(buffer.get(), filesize); if (actual != filesize) { log_info("Configuration file:" << filename << " read error"); return false; } log_info("Configuration file:" << filename); - bool retval = load(new StringRange(buffer, buffer + filesize)); - delete[] buffer; - return retval; + // Trimming the overall config file could influence indentation, hence false + return load_yaml(std::string_view { buffer.get(), filesize }); } catch (...) { log_warn("Cannot open configuration file:" << filename); return false; } } - bool MachineConfig::load(StringRange* input) { + bool MachineConfig::load_yaml(std::string_view input) { bool successful = false; try { - Configuration::Parser parser(input->begin(), input->end()); + Configuration::Parser parser(input); Configuration::ParserHandler handler(parser); // instance() is by reference, so we can just get rid of an old instance and @@ -255,7 +256,6 @@ namespace Machine { // Get rid of buffer and return log_error("Unknown error while processing config file"); } - delete[] input; std::atomic_thread_fence(std::memory_order::memory_order_seq_cst); diff --git a/FluidNC/src/Machine/MachineConfig.h b/FluidNC/src/Machine/MachineConfig.h index 8f5ff270c..9f33ae328 100644 --- a/FluidNC/src/Machine/MachineConfig.h +++ b/FluidNC/src/Machine/MachineConfig.h @@ -20,6 +20,7 @@ #include "../Stepper.h" #include "../Config.h" #include "../OLED.h" +#include "../Status_outputs.h" #include "Axes.h" #include "SPIBus.h" #include "I2CBus.h" @@ -27,6 +28,8 @@ #include "UserOutputs.h" #include "Macros.h" +#include + namespace Machine { using ::Kinematics::Kinematics; @@ -72,6 +75,7 @@ namespace Machine { Start* _start = nullptr; Parking* _parking = nullptr; OLED* _oled = nullptr; + Status_Outputs* _stat_out = nullptr; Spindles::SpindleList _spindles; UartChannel* _uart_channels[MAX_N_UARTS] = { nullptr }; @@ -107,8 +111,8 @@ namespace Machine { void group(Configuration::HandlerBase& handler) override; static bool load(); - static bool load(const char* file); - static bool load(StringRange* input); + static bool load_file(std::string_view file); + static bool load_yaml(std::string_view yaml_string); ~MachineConfig(); }; diff --git a/FluidNC/src/Machine/Macros.cpp b/FluidNC/src/Machine/Macros.cpp index a493af8ea..f15917c69 100644 --- a/FluidNC/src/Machine/Macros.cpp +++ b/FluidNC/src/Machine/Macros.cpp @@ -6,15 +6,18 @@ #include "src/System.h" // sys #include "src/Machine/MachineConfig.h" // config +Macro::Macro(const char* name) : _name(name) {} + void MacroEvent::run(void* arg) { - if (sys.state != State::Idle) { - log_error("Macro can only be used in idle state"); - return; - } - log_debug("Macro " << _num); - config->_macros->run_macro(_num); + config->_macros->_macro[_num].run(); } +Macro Macros::_startup_line[n_startup_lines] = { "startup_line0", "startup_line1" }; +Macro Macros::_macro[n_macros] = { "macro0", "macro1", "macro2", "macro3" }; +Macro Macros::_after_homing = { "after_homing" }; +Macro Macros::_after_reset = { "after_reset" }; +Macro Macros::_after_unlock = { "after_unlock" }; + MacroEvent macro0Event { 0 }; MacroEvent macro1Event { 1 }; MacroEvent macro2Event { 2 }; @@ -47,18 +50,21 @@ Cmd findOverride(std::string name) { return it == overrideCodes.end() ? Cmd::None : it->second; } -bool Macros::run_macro(size_t index) { - if (index >= n_macros) { +bool Macro::run() { + if (sys.state != State::Idle) { + log_error("Macro can only be used in idle state"); return false; } - auto macro = _macro[index]; - if (macro == "") { - return true; + + const std::string& s = _gcode; + if (_gcode == "") { + return false; } + log_info("Running macro " << _name << ": " << _gcode); char c; - for (int i = 0; i < macro.length(); i++) { - c = macro[i]; + for (int i = 0; i < _gcode.length(); i++) { + c = _gcode[i]; switch (c) { case '&': // & is a proxy for newlines in macros, because you cannot @@ -66,13 +72,13 @@ bool Macros::run_macro(size_t index) { WebUI::inputBuffer.push('\n'); break; case '#': - if ((i + 3) > macro.length()) { + if ((i + 3) > _gcode.length()) { log_error("Missing characters after # realtime escape in macro"); return false; } { - std::string s(macro.c_str() + i + 1, 2); - Cmd cmd = findOverride(s); + std::string s1(_gcode.c_str() + i + 1, 2); + Cmd cmd = findOverride(s1); if (cmd == Cmd::None) { log_error("Bad #xx realtime escape in macro"); return false; diff --git a/FluidNC/src/Machine/Macros.h b/FluidNC/src/Machine/Macros.h index ac785b10f..80358fd01 100644 --- a/FluidNC/src/Machine/Macros.h +++ b/FluidNC/src/Machine/Macros.h @@ -24,45 +24,41 @@ extern MacroEvent macro2Event; extern MacroEvent macro3Event; namespace Machine { + class Macro { + public: + std::string _gcode; + const char* _name; + Macro(const char* name); + bool run(); + }; + class Macros : public Configuration::Configurable { public: static const int n_startup_lines = 2; static const int n_macros = 4; - private: - std::string _startup_line[n_startup_lines]; - std::string _macro[n_macros]; + static Macro _macro[n_macros]; + static Macro _startup_line[n_startup_lines]; + static Macro _after_homing; + static Macro _after_reset; + static Macro _after_unlock; - public: Macros() = default; - bool run_macro(size_t index); - - std::string startup_line(size_t index) { - if (index >= n_startup_lines) { - return ""; - } - auto s = _startup_line[index]; - if (s == "") { - return s; - } - // & is a proxy for newlines in startup lines, because you cannot - // enter a newline directly in a config file string value. - std::replace(s.begin(), s.end(), '&', '\n'); - return s + "\n"; - } - // Configuration helpers: // TODO: We could validate the startup lines void group(Configuration::HandlerBase& handler) override { - handler.item("startup_line0", _startup_line[0]); - handler.item("startup_line1", _startup_line[1]); - handler.item("macro0", _macro[0]); - handler.item("macro1", _macro[1]); - handler.item("macro2", _macro[2]); - handler.item("macro3", _macro[3]); + handler.item(_startup_line[0]._name, _startup_line[0]._gcode); + handler.item(_startup_line[1]._name, _startup_line[1]._gcode); + handler.item(_macro[0]._name, _macro[0]._gcode); + handler.item(_macro[1]._name, _macro[1]._gcode); + handler.item(_macro[2]._name, _macro[2]._gcode); + handler.item(_macro[3]._name, _macro[3]._gcode); + handler.item(_after_homing._name, _after_homing._gcode); + handler.item(_after_reset._name, _after_reset._gcode); + handler.item(_after_unlock._name, _after_unlock._gcode); } ~Macros() {} diff --git a/FluidNC/src/Machine/UserOutputs.cpp b/FluidNC/src/Machine/UserOutputs.cpp index 2aea2616d..6aebe2d38 100644 --- a/FluidNC/src/Machine/UserOutputs.cpp +++ b/FluidNC/src/Machine/UserOutputs.cpp @@ -40,6 +40,8 @@ namespace Machine { void UserOutputs::all_off() { for (size_t io_num = 0; io_num < MaxUserDigitalPin; io_num++) { setDigital(io_num, false); + } + for (size_t io_num = 0; io_num < MaxUserAnalogPin; io_num++) { setAnalogPercent(io_num, 0); } } @@ -61,14 +63,14 @@ namespace Machine { return percent == 0.0; } - uint32_t duty = uint32_t(percent / 100.0f * _denominator[io_num]); - auto pwm = _pwm[io_num]; if (!pwm) { log_error("M67 PWM channel error"); return false; } + uint32_t duty = uint32_t(percent * pwm->period() / 100.0f); + if (_current_value[io_num] == duty) { return true; } @@ -93,5 +95,9 @@ namespace Machine { handler.item("digital1_pin", _digitalOutput[1]); handler.item("digital2_pin", _digitalOutput[2]); handler.item("digital3_pin", _digitalOutput[3]); + handler.item("digital4_pin", _digitalOutput[4]); + handler.item("digital5_pin", _digitalOutput[5]); + handler.item("digital6_pin", _digitalOutput[6]); + handler.item("digital7_pin", _digitalOutput[7]); } } diff --git a/FluidNC/src/Machine/UserOutputs.h b/FluidNC/src/Machine/UserOutputs.h index 8d94af118..9aa5878b4 100644 --- a/FluidNC/src/Machine/UserOutputs.h +++ b/FluidNC/src/Machine/UserOutputs.h @@ -12,7 +12,6 @@ namespace Machine { class UserOutputs : public Configuration::Configurable { PwmPin* _pwm[MaxUserAnalogPin]; uint32_t _current_value[MaxUserAnalogPin]; - uint32_t _denominator[MaxUserAnalogPin]; public: UserOutputs(); diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 1462e3c95..c9276a25f 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -31,8 +31,9 @@ void setup() { disableCore0WDT(); try { timing_init(); - uartInit(); // Setup serial port - Uart0.println(); // create some white space after ESP32 boot info + uartInit(); // Setup serial port + + StartupLog::init(); // Setup input polling loop after loading the configuration, // because the polling may depend on the config @@ -47,7 +48,7 @@ void setup() { // Load settings from non-volatile storage settings_init(); // requires config - log_info("FluidNC " << git_info); + log_info("FluidNC " << git_info << " " << git_url); log_info("Compiled with ESP32 SDK:" << esp_get_idf_version()); if (localfs_mount()) { @@ -96,6 +97,10 @@ void setup() { config->_oled->init(); } + if (config->_stat_out) { + config->_stat_out->init(); + } + config->_stepping->init(); // Configure stepper interrupt timers plan_init(); @@ -107,30 +112,12 @@ void setup() { config->_control->init(); config->_kinematics->init(); + + limits_init(); } // Initialize system state. if (sys.state != State::ConfigAlarm) { - if (FORCE_INITIALIZATION_ALARM) { - // Force ALARM state upon a power-cycle or hard reset. - sys.state = State::Alarm; - } else { - sys.state = State::Idle; - } - - limits_init(); - - // Check for power-up and set system alarm if homing is enabled to force homing cycle - // by setting alarm state. Alarm locks out all g-code commands, including the - // startup scripts, but allows access to settings and internal commands. Only a homing - // cycle '$H' or kill alarm locks '$X' will disable the alarm. - // NOTE: The startup script will run after successful completion of the homing cycle, but - // not after disabling the alarm locks. Prevents motion startup blocks from crashing into - // things uncontrollably. Very bad. - if (config->_start->_mustHome && Machine::Axes::homingMask) { - // If there is an axis with homing configured, enter Alarm state on startup - sys.state = State::Alarm; - } for (auto s : config->_spindles) { s->init(); } @@ -146,44 +133,20 @@ void setup() { sys.state = State::ConfigAlarm; } - if (!WebUI::wifi_config.begin()) { - WebUI::bt_config.begin(); - } - allChannels.deregistration(&startupLog); -} - -static void reset_variables() { - // Reset primary systems. - system_reset(); - protocol_reset(); - gc_init(); // Set g-code parser to default state - // Spindle should be set either by the configuration - // or by the post-configuration fixup, but we test - // it anyway just for safety. We want to avoid any - // possibility of crashing at this point. - - plan_reset(); // Clear block buffer and planner variables - - if (sys.state != State::ConfigAlarm) { - if (spindle) { - spindle->stop(); - report_ovr_counter = 0; // Set to report change immediately - } - Stepper::reset(); // Clear stepper subsystem variables + // Try Bluetooth first so its memory can be released if it is disabled + if (!WebUI::bt_config.begin()) { + WebUI::wifi_config.begin(); } - // Sync cleared gcode and planner positions to current system position. - plan_sync_position(); - gc_sync_position(); - allChannels.flushRx(); - report_init_message(allChannels); - mc_init(); + allChannels.ready(); + allChannels.deregistration(&startupLog); + protocol_send_event(&startEvent); } void loop() { + vTaskPrioritySet(NULL, 2); static int tries = 0; try { - reset_variables(); // Start the main loop. Processes program inputs and executes them. // This can exit on a system abort condition, in which case run_once() // is re-executed by an enclosing loop. It can also exit via a diff --git a/FluidNC/src/MotionControl.cpp b/FluidNC/src/MotionControl.cpp index 9c986f8dd..86d69bb39 100644 --- a/FluidNC/src/MotionControl.cpp +++ b/FluidNC/src/MotionControl.cpp @@ -101,12 +101,20 @@ void mc_cancel_jog() { // Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second // unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in // (1 minute)/feed_rate time. -bool mc_linear(float* target, plan_line_data_t* pl_data, float* position) { - if (!pl_data->is_jog) { // soft limits for jogs have already been dealt with - limits_soft_check(target); - } + +// mc_linear_no_check() is used by mc_arc() which pre-checks the arc limits using +// a fast algorithm, so checking each segment is unnecessary. +static bool mc_linear_no_check(float* target, plan_line_data_t* pl_data, float* position) { return config->_kinematics->cartesian_to_motors(target, pl_data, position); } +bool mc_linear(float* target, plan_line_data_t* pl_data, float* position) { + if (!pl_data->is_jog && !pl_data->limits_checked) { // soft limits for jogs have already been dealt with + if (config->_kinematics->invalid_line(target)) { + return false; + } + } + return mc_linear_no_check(target, pl_data, position); +} // Execute an arc in offset mode format. position == current xyz, target == target xyz, // offset == offset from current xyz, axis_X defines circle plane in tool space, axis_linear is @@ -125,12 +133,17 @@ void mc_arc(float* target, size_t axis_linear, bool is_clockwise_arc, int pword_rotations) { - float center_axis0 = position[axis_0] + offset[axis_0]; - float center_axis1 = position[axis_1] + offset[axis_1]; - float r_axis0 = -offset[axis_0]; // Radius vector from center to current location - float r_axis1 = -offset[axis_1]; - float rt_axis0 = target[axis_0] - center_axis0; - float rt_axis1 = target[axis_1] - center_axis1; + float center[3] = { position[axis_0] + offset[axis_0], position[axis_1] + offset[axis_1], 0 }; + + // The first two axes are the circle plane and the third is the orthogonal plane + size_t caxes[3] = { axis_0, axis_1, axis_linear }; + if (config->_kinematics->invalid_arc(target, pl_data, position, center, radius, caxes, is_clockwise_arc)) { + return; + } + + // Radius vector from center to current location + float radii[2] = { -offset[axis_0], -offset[axis_1] }; + float rt[2] = { target[axis_0] - center[0], target[axis_1] - center[1] }; auto n_axis = config->_axes->_numberAxis; @@ -140,7 +153,7 @@ void mc_arc(float* target, } // CCW angle between position and target from circle center. Only one atan2() trig computation required. - float angular_travel = atan2f(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1); + float angular_travel = atan2f(radii[0] * rt[1] - radii[1] * rt[0], radii[0] * rt[0] + radii[1] * rt[1]); if (is_clockwise_arc) { // Correct atan2 output per direction if (angular_travel >= -ARC_ANGULAR_TRAVEL_EPSILON) { angular_travel -= 2 * float(M_PI); @@ -211,29 +224,28 @@ void mc_arc(float* target, cos_T *= 0.5; float sin_Ti; float cos_Ti; - float r_axisi; uint16_t i; size_t count = 0; float original_feedrate = pl_data->feed_rate; // Kinematics may alter the feedrate, so save an original copy for (i = 1; i < segments; i++) { // Increment (segments-1). if (count < N_ARC_CORRECTION) { // Apply vector rotation matrix. ~40 usec - r_axisi = r_axis0 * sin_T + r_axis1 * cos_T; - r_axis0 = r_axis0 * cos_T - r_axis1 * sin_T; - r_axis1 = r_axisi; + float ri = radii[0] * sin_T + radii[1] * cos_T; + radii[0] = radii[0] * cos_T - radii[1] * sin_T; + radii[1] = ri; count++; } else { // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. ~375 usec // Compute exact location by applying transformation matrix from initial radius vector(=-offset). - cos_Ti = cosf(i * theta_per_segment); - sin_Ti = sinf(i * theta_per_segment); - r_axis0 = -offset[axis_0] * cos_Ti + offset[axis_1] * sin_Ti; - r_axis1 = -offset[axis_0] * sin_Ti - offset[axis_1] * cos_Ti; - count = 0; + cos_Ti = cosf(i * theta_per_segment); + sin_Ti = sinf(i * theta_per_segment); + radii[0] = -offset[axis_0] * cos_Ti + offset[axis_1] * sin_Ti; + radii[1] = -offset[axis_0] * sin_Ti - offset[axis_1] * cos_Ti; + count = 0; } // Update arc_target location - position[axis_0] = center_axis0 + r_axis0; - position[axis_1] = center_axis1 + r_axis1; + position[axis_0] = center[0] + radii[0]; + position[axis_1] = center[1] + radii[1]; position[axis_linear] += linear_per_segment[axis_linear]; for (size_t i = A_AXIS; i < n_axis; i++) { position[i] += linear_per_segment[i]; @@ -291,7 +303,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, bool away, // After syncing, check if probe is already triggered. If so, halt and issue alarm. // NOTE: This probe initialization error applies to all probing cycles. if (config->_probe->tripped()) { - rtAlarm = ExecAlarm::ProbeFailInitial; + send_alarm(ExecAlarm::ProbeFailInitial); protocol_execute_realtime(); config->_stepping->endLowLatency(); return GCUpdatePos::None; // Nothing else to do but bail. @@ -318,7 +330,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, bool away, if (no_error) { copyAxes(probe_steps, get_motor_steps()); } else { - rtAlarm = ExecAlarm::ProbeFailContact; + send_alarm(ExecAlarm::ProbeFailContact); } } else { probe_succeeded = true; // Indicate to system the probing cycle completed successfully. @@ -372,26 +384,11 @@ void mc_override_ctrl_update(Override override_state) { // active processes in the system. This also checks if a system reset is issued while in // motion state. If so, kills the steppers and sets the system alarm to flag position // lost, since there was an abrupt uncontrolled deceleration. Called at an interrupt level by -// realtime abort command and hard limits. So, keep to a minimum. Stuff that cannot be -// done quickly is handled later when Protocol.cpp responds to rtReset. -void mc_reset() { - // Only this function can set the system reset. Helps prevent multiple kill calls. - if (!rtReset) { - rtReset = true; - - // Kill steppers only if in any motion state, i.e. cycle, actively holding, or homing. - // NOTE: If steppers are kept enabled via the step idle delay setting, this also keeps - // the steppers enabled by avoiding the go_idle call altogether, unless the motion state is - // violated, by which, all bets are off. - if (inMotionState() || sys.step_control.executeHold || sys.step_control.executeSysMotion) { - if (sys.state == State::Homing) { - if (rtAlarm == ExecAlarm::None) { - rtAlarm = ExecAlarm::HomingFailReset; - } - } else { - rtAlarm = ExecAlarm::AbortCycle; - } - Stepper::stop_stepping(); // Stop stepping immediately, possibly losing position - } +// realtime abort command and hard limits. So, keep to a minimum. +void mc_critical(ExecAlarm alarm) { + if (inMotionState() || sys.step_control.executeHold || sys.step_control.executeSysMotion) { + Stepper::reset(); // Stop stepping immediately, possibly losing position + // Stepper::stop_stepping(); // Stop stepping immediately, possibly losing position } + send_alarm(alarm); } diff --git a/FluidNC/src/MotionControl.h b/FluidNC/src/MotionControl.h index df51a154c..f379113fe 100644 --- a/FluidNC/src/MotionControl.h +++ b/FluidNC/src/MotionControl.h @@ -19,12 +19,6 @@ extern bool probe_succeeded; // Tracks if last probing cycle was successful. // System motion commands must have a line number of zero. const int PARKING_MOTION_LINE_NUMBER = 0; -// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second -// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in -// (1 minute)/feed_rate time. -bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position); -void motors_to_cartesian(float* cartesian, float* motors, int n_axis); - // Execute a linear motion in cartesian space. bool mc_linear(float* target, plan_line_data_t* pl_data, float* position); @@ -56,7 +50,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, bool away, void mc_override_ctrl_update(Override override_state); // Performs system reset. If in motion state, kills all motion and sets system alarm. -void mc_reset(); +void mc_critical(ExecAlarm alarm); void mc_cancel_jog(); diff --git a/FluidNC/src/Motors/Dynamixel2.cpp b/FluidNC/src/Motors/Dynamixel2.cpp index 0c01cc258..ac573b4b7 100644 --- a/FluidNC/src/Motors/Dynamixel2.cpp +++ b/FluidNC/src/Motors/Dynamixel2.cpp @@ -90,16 +90,16 @@ namespace MotorDrivers { if (len == PING_RSP_LEN) { uint16_t model_num = _rx_message[10] << 8 | _rx_message[9]; uint8_t fw_rev = _rx_message[11]; - std::string msg("Axis ping reply "); + std::string msg(" "); msg += axisName().c_str(); if (model_num == 1060) { - msg += " Model XL430-W250"; + msg += "reply: Model XL430-W250"; } else { msg += " M/N " + std::to_string(model_num); } log_info(msg << " F/W Rev " << to_hex(fw_rev)); } else { - log_warn(" Ping failed"); + log_warn(axisName() << " Ping failed"); return false; } @@ -158,7 +158,9 @@ namespace MotorDrivers { } finish_message(); } - void Dynamixel2::update() { update_all(); } + void Dynamixel2::update() { + update_all(); + } void Dynamixel2::set_location() {} @@ -177,7 +179,9 @@ namespace MotorDrivers { return false; // Cannot do conventional homing } - void Dynamixel2::add_uint8(uint8_t n) { _tx_message[_msg_index++] = n & 0xff; } + void Dynamixel2::add_uint8(uint8_t n) { + _tx_message[_msg_index++] = n & 0xff; + } void Dynamixel2::add_uint16(uint16_t n) { add_uint8(n); add_uint8(n >> 8); diff --git a/FluidNC/src/Motors/StandardStepper.cpp b/FluidNC/src/Motors/StandardStepper.cpp index fa519ffcc..20b3aec2b 100644 --- a/FluidNC/src/Motors/StandardStepper.cpp +++ b/FluidNC/src/Motors/StandardStepper.cpp @@ -84,7 +84,9 @@ namespace MotorDrivers { _step_pin.setAttr(Pin::Attr::Output); } - _disable_pin.setAttr(Pin::Attr::Output); + if (_disable_pin.defined()) { + _disable_pin.setAttr(Pin::Attr::Output); + } } void StandardStepper::config_message() { diff --git a/FluidNC/src/Motors/TMC2208Driver.cpp b/FluidNC/src/Motors/TMC2208Driver.cpp index 7434b8a84..b43457fe4 100644 --- a/FluidNC/src/Motors/TMC2208Driver.cpp +++ b/FluidNC/src/Motors/TMC2208Driver.cpp @@ -26,8 +26,10 @@ namespace MotorDrivers { } void TMC2208Driver::config_motor() { + _cs_pin.synchronousWrite(true); tmc2208->begin(); TrinamicBase::config_motor(); + _cs_pin.synchronousWrite(false); } void TMC2208Driver::set_registers(bool isHoming) { @@ -41,6 +43,9 @@ namespace MotorDrivers { // but the TMCStepper library expresses run current as (uint16_t) mA // and hold current as (float) fraction of run current. uint16_t run_i = (uint16_t)(_run_current * 1000.0); + + _cs_pin.synchronousWrite(true); + tmc2208->I_scale_analog(false); // do not scale via pot tmc2208->rms_current(run_i, TrinamicBase::holdPercent()); @@ -51,20 +56,26 @@ namespace MotorDrivers { // This driver does not support multiple modes tmc2208->en_spreadCycle(false); tmc2208->pwm_autoscale(true); + + _cs_pin.synchronousWrite(false); } void TMC2208Driver::debug_message() {} void TMC2208Driver::set_disable(bool disable) { + _cs_pin.synchronousWrite(true); if (TrinamicUartDriver::startDisable(disable)) { if (_use_enable) { tmc2208->toff(TrinamicUartDriver::toffValue()); } } + _cs_pin.synchronousWrite(false); } bool TMC2208Driver::test() { + _cs_pin.synchronousWrite(true); if (!checkVersion(0x20, tmc2208->version())) { + _cs_pin.synchronousWrite(false); return false; } uint8_t ifcnt_before = tmc2208->IFCNT(); @@ -73,8 +84,10 @@ namespace MotorDrivers { bool okay = ((ifcnt_before + 1) & 0xff) == ifcnt_after; if (!okay) { TrinamicBase::reportCommsFailure(); + _cs_pin.synchronousWrite(false); return false; } + _cs_pin.synchronousWrite(false); return true; } diff --git a/FluidNC/src/Motors/TMC2209Driver.cpp b/FluidNC/src/Motors/TMC2209Driver.cpp index 6ca5ee117..cb87bd18e 100644 --- a/FluidNC/src/Motors/TMC2209Driver.cpp +++ b/FluidNC/src/Motors/TMC2209Driver.cpp @@ -27,8 +27,10 @@ namespace MotorDrivers { } void TMC2209Driver::config_motor() { + _cs_pin.synchronousWrite(true); tmc2209->begin(); TrinamicBase::config_motor(); + _cs_pin.synchronousWrite(false); } void TMC2209Driver::set_registers(bool isHoming) { @@ -42,6 +44,9 @@ namespace MotorDrivers { // but the TMCStepper library expresses run current as (uint16_t) mA // and hold current as (float) fraction of run current. uint16_t run_i = (uint16_t)(_run_current * 1000.0); + + _cs_pin.synchronousWrite(true); + tmc2209->I_scale_analog(false); // do not scale via pot tmc2209->rms_current(run_i, TrinamicBase::holdPercent()); @@ -75,13 +80,15 @@ namespace MotorDrivers { } // dump the registers. This is helpful for people migrating to the Pro version - log_debug("CHOPCONF: 0x" << to_hex(tmc2209->CHOPCONF())); - log_debug("COOLCONF: 0x" << to_hex(tmc2209->COOLCONF())); - log_debug("TPWMTHRS: 0x" << to_hex(tmc2209->TPWMTHRS())); - log_debug("TCOOLTHRS: 0x" << to_hex(tmc2209->TCOOLTHRS())); - log_debug("GCONF: 0x" << to_hex(tmc2209->GCONF())); - log_debug("PWMCONF: 0x" << to_hex(tmc2209->PWMCONF())); - log_debug("IHOLD_IRUN: 0x" << to_hex(tmc2209->IHOLD_IRUN())); + log_verbose("CHOPCONF: " << to_hex(tmc2209->CHOPCONF())); + log_verbose("COOLCONF: " << to_hex(tmc2209->COOLCONF())); + log_verbose("TPWMTHRS: " << to_hex(tmc2209->TPWMTHRS())); + log_verbose("TCOOLTHRS: " << to_hex(tmc2209->TCOOLTHRS())); + log_verbose("GCONF: " << to_hex(tmc2209->GCONF())); + log_verbose("PWMCONF: " << to_hex(tmc2209->PWMCONF())); + log_verbose("IHOLD_IRUN: " << to_hex(tmc2209->IHOLD_IRUN())); + + _cs_pin.synchronousWrite(false); } void TMC2209Driver::debug_message() { @@ -89,9 +96,12 @@ namespace MotorDrivers { return; } + _cs_pin.synchronousWrite(true); + uint32_t tstep = tmc2209->TSTEP(); if (tstep == 0xFFFFF || tstep < 1) { // if axis is not moving return + _cs_pin.synchronousWrite(false); return; } float feedrate = Stepper::get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz @@ -99,28 +109,37 @@ namespace MotorDrivers { if (tmc2209) { log_info(axisName() << " SG_Val: " << tmc2209->SG_RESULT() << " Rate: " << feedrate << " mm/min SG_Setting:" << _stallguard); } + + _cs_pin.synchronousWrite(false); } void TMC2209Driver::set_disable(bool disable) { + _cs_pin.synchronousWrite(true); if (TrinamicUartDriver::startDisable(disable)) { if (_use_enable) { tmc2209->toff(TrinamicUartDriver::toffValue()); } } + _cs_pin.synchronousWrite(false); } bool TMC2209Driver::test() { + _cs_pin.synchronousWrite(true); if (!checkVersion(0x21, tmc2209->version())) { + _cs_pin.synchronousWrite(false); return false; } + uint8_t ifcnt_before = tmc2209->IFCNT(); tmc2209->GSTAT(0); // clear GSTAT to increase ifcnt uint8_t ifcnt_after = tmc2209->IFCNT(); bool okay = ((ifcnt_before + 1) & 0xff) == ifcnt_after; if (!okay) { TrinamicBase::reportCommsFailure(); + _cs_pin.synchronousWrite(false); return false; } + _cs_pin.synchronousWrite(false); return true; } diff --git a/FluidNC/src/Motors/TMC5160Driver.cpp b/FluidNC/src/Motors/TMC5160Driver.cpp index b47ce261c..8a05b116b 100644 --- a/FluidNC/src/Motors/TMC5160Driver.cpp +++ b/FluidNC/src/Motors/TMC5160Driver.cpp @@ -80,13 +80,13 @@ namespace MotorDrivers { } } // dump the registers. This is helpful for people migrating to the Pro version - log_debug("CHOPCONF: 0x" << to_hex(tmc5160->CHOPCONF())); - log_debug("COOLCONF: 0x" << to_hex(tmc5160->COOLCONF())); - log_debug("THIGH: 0x" << to_hex(tmc5160->THIGH())); - log_debug("TCOOLTHRS: 0x" << to_hex(tmc5160->TCOOLTHRS())); - log_debug("GCONF: 0x" << to_hex(tmc5160->GCONF())); - log_debug("PWMCONF: 0x" << to_hex(tmc5160->PWMCONF())); - log_debug("IHOLD_IRUN: 0x" << to_hex(tmc5160->IHOLD_IRUN())); + log_verbose("CHOPCONF: " << to_hex(tmc5160->CHOPCONF())); + log_verbose("COOLCONF: " << to_hex(tmc5160->COOLCONF())); + log_verbose("THIGH: " << to_hex(tmc5160->THIGH())); + log_verbose("TCOOLTHRS: " << to_hex(tmc5160->TCOOLTHRS())); + log_verbose("GCONF: " << to_hex(tmc5160->GCONF())); + log_verbose("PWMCONF: " << to_hex(tmc5160->PWMCONF())); + log_verbose("IHOLD_IRUN: " << to_hex(tmc5160->IHOLD_IRUN())); } // Report diagnostic and tuning info diff --git a/FluidNC/src/Motors/TrinamicBase.cpp b/FluidNC/src/Motors/TrinamicBase.cpp index ba6324600..356ebb7ee 100644 --- a/FluidNC/src/Motors/TrinamicBase.cpp +++ b/FluidNC/src/Motors/TrinamicBase.cpp @@ -106,7 +106,7 @@ namespace MotorDrivers { bool TrinamicBase::checkVersion(uint8_t expected, uint8_t got) { if (expected != got) { - log_error(axisName() << " TMC driver not detected - expected 0x" << to_hex(expected) << " got 0x" << to_hex(got)); + log_error(axisName() << " TMC driver not detected - expected " << to_hex(expected) << " got " << to_hex(got)); return false; } log_info(axisName() << " driver test passed"); @@ -146,7 +146,7 @@ namespace MotorDrivers { // Display the stepper library version message once, before the first // TMC config message. if (_instances.empty()) { - log_debug("TMCStepper Library Ver. 0x" << to_hex(TMCSTEPPER_VERSION)); + log_debug("TMCStepper Library Ver. " << to_hex(TMCSTEPPER_VERSION)); auto timer = xTimerCreate("Stallguard", 200, true, nullptr, read_sg); // Timer failure is not fatal because you can still use the system if (!timer) { diff --git a/FluidNC/src/Motors/TrinamicUartDriver.cpp b/FluidNC/src/Motors/TrinamicUartDriver.cpp index 3533f9e39..97ac24729 100644 --- a/FluidNC/src/Motors/TrinamicUartDriver.cpp +++ b/FluidNC/src/Motors/TrinamicUartDriver.cpp @@ -21,18 +21,19 @@ namespace MotorDrivers { void TrinamicUartDriver::init() { _uart = config->_uarts[_uart_num]; - if (!_uart) { - log_error("TMC2208: Missing uart" << _uart_num << "section"); - return; - } + Assert(_uart, "TMC Driver missing uart%d section", _uart_num); + + _cs_pin.setAttr(Pin::Attr::Output); } /* This is the startup message showing the basic definition. + + log_info(" UART CS:" << ); */ void TrinamicUartDriver::config_message() { //TODO: The RX/TX pin could be added to the msg. - log_info(" " << name() << " UART" << _uart_num << " Addr:" << _addr << " Step:" << _step_pin.name() << " Dir:" << _dir_pin.name() - << " Disable:" << _disable_pin.name() << " R:" << _r_sense); + log_info(" " << name() << " UART" << _uart_num << " Addr:" << _addr << " CS:" << _cs_pin.name() << " Step:" << _step_pin.name() + << " Dir:" << _dir_pin.name() << " Disable:" << _disable_pin.name() << " R:" << _r_sense); } uint8_t TrinamicUartDriver::toffValue() { diff --git a/FluidNC/src/Motors/TrinamicUartDriver.h b/FluidNC/src/Motors/TrinamicUartDriver.h index 081755763..5d12568d1 100644 --- a/FluidNC/src/Motors/TrinamicUartDriver.h +++ b/FluidNC/src/Motors/TrinamicUartDriver.h @@ -17,13 +17,6 @@ namespace MotorDrivers { TrinamicUartDriver() = default; void init() override; - //void read_settings() override; - //bool set_homing_mode(bool is_homing) override; - void set_disable(bool disable) override; - - void debug_message(); - - bool hw_serial_init(); uint8_t _addr; @@ -37,13 +30,17 @@ namespace MotorDrivers { void group(Configuration::HandlerBase& handler) override { handler.item("addr", _addr); + handler.item("cs_pin", _cs_pin); handler.item("uart_num", _uart_num); + TrinamicBase::group(handler); } protected: Uart* _uart = nullptr; + Pin _cs_pin; + int _uart_num = -1; static bool _uart_started; @@ -52,8 +49,7 @@ namespace MotorDrivers { uint8_t toffValue(); // TO DO move to Base? private: - bool test(); - void set_mode(bool isHoming); + }; } diff --git a/FluidNC/src/MyIOStream.h b/FluidNC/src/MyIOStream.h index 157bc6045..8e155391d 100644 --- a/FluidNC/src/MyIOStream.h +++ b/FluidNC/src/MyIOStream.h @@ -6,9 +6,9 @@ #include #include #include +#include #include "Pin.h" -#include "StringRange.h" std::string IP_string(uint32_t ipaddr); @@ -22,14 +22,14 @@ inline Print& operator<<(Print& lhs, const char* v) { return lhs; } -inline Print& operator<<(Print& lhs, const StringRange& s) { - for (const char* p = s.begin(); p < s.end(); ++p) { +inline Print& operator<<(Print& lhs, const std::string_view& v) { + for (const char* p = v.cbegin(); p < v.cend(); ++p) { lhs.print(*p); } return lhs; } -inline Print& operator<<(Print& lhs, std::string v) { +inline Print& operator<<(Print& lhs, const std::string& v) { lhs.print(v.c_str()); return lhs; } diff --git a/FluidNC/src/NutsBolts.cpp b/FluidNC/src/NutsBolts.cpp index fb7271d4e..ac5070779 100644 --- a/FluidNC/src/NutsBolts.cpp +++ b/FluidNC/src/NutsBolts.cpp @@ -241,7 +241,7 @@ std::string formatBytes(uint64_t bytes) { b /= 1024; if (b < 1024) { std::ostringstream msg; - msg << std::fixed << std::setprecision(2) << b << " TB"; + msg << std::fixed << std::setprecision(2) << b << " GB"; return msg.str(); } b /= 1024; @@ -249,7 +249,7 @@ std::string formatBytes(uint64_t bytes) { b = 99999; } std::ostringstream msg; - msg << std::fixed << std::setprecision(2) << b << " GB"; + msg << std::fixed << std::setprecision(2) << b << " TB"; return msg.str(); } diff --git a/FluidNC/src/NutsBolts.h b/FluidNC/src/NutsBolts.h index 248649d65..162dc1a43 100644 --- a/FluidNC/src/NutsBolts.h +++ b/FluidNC/src/NutsBolts.h @@ -59,7 +59,7 @@ bool read_float(const char* line, size_t* char_counter, float* float_ptr); void delay_us(int32_t microseconds); // Delay while checking for realtime characters and other events -bool delay_msec(uint32_t milliseconds, DwellMode mode); +bool delay_msec(uint32_t milliseconds, DwellMode mode = DwellMode::Dwell); // Delay without checking for realtime events. Use only for short delays void delay_ms(uint16_t ms); @@ -85,13 +85,6 @@ const char* to_hex(uint32_t n); bool char_is_numeric(char value); char* trim(char* value); -template -void swap(T& a, T& b) { - T c(a); - a = b; - b = c; -} - template T myMap(T x, T in_min, T in_max, T out_min, T out_max) { // DrawBot_Badge return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; diff --git a/FluidNC/src/OLED.cpp b/FluidNC/src/OLED.cpp index ec7c9a501..b41478578 100644 --- a/FluidNC/src/OLED.cpp +++ b/FluidNC/src/OLED.cpp @@ -67,7 +67,7 @@ void OLED::init() { if (_error) { return; } - log_info("OLED I2C address:" << to_hex(_address) << " width: " << _width << " height: " << _height); + log_info("OLED I2C address: " << to_hex(_address) << " width: " << _width << " height: " << _height); _oled = new SSD1306_I2C(_address, _geometry, config->_i2c[_i2c_num], 400000); _oled->init(); @@ -81,7 +81,7 @@ void OLED::init() { _oled->display(); allChannels.registration(this); - setReportInterval(500); + setReportInterval(_report_interval_ms); } Channel* OLED::pollLine(char* line) { @@ -205,9 +205,7 @@ void OLED::parse_numbers(std::string s, float* nums, int maxnums) { } while (nextpos != std::string::npos); } -float* OLED::parse_axes(std::string s) { - static float axes[MAX_N_AXIS]; - +void OLED::parse_axes(std::string s, float* axes) { size_t pos = 0; size_t nextpos = -1; size_t axis = 0; @@ -219,7 +217,6 @@ float* OLED::parse_axes(std::string s) { } pos = nextpos + 1; } while (nextpos != std::string::npos); - return axes; } void OLED::parse_status_report() { @@ -234,9 +231,9 @@ void OLED::parse_status_report() { bool probe = false; bool limits[MAX_N_AXIS] = { false }; - float* axes; - bool isMpos = false; - _filename = ""; + float axes[MAX_N_AXIS]; + bool isMpos = false; + _filename = ""; // ... handle it while (nextpos != std::string::npos) { @@ -249,13 +246,13 @@ void OLED::parse_status_report() { auto value = field.substr(colon + 1); if (tag == "MPos") { // x,y,z,... - axes = parse_axes(value); + parse_axes(value, axes); isMpos = true; continue; } if (tag == "WPos") { // x,y,z... - axes = parse_axes(value); + parse_axes(value, axes); isMpos = false; continue; } @@ -305,7 +302,10 @@ void OLED::parse_status_report() { } if (tag == "WCO") { // x,y,z,... - auto wcos = parse_axes(value); + // We do not use the WCO values because the DROs show whichever + // position is in the status report + // float wcos[MAX_N_AXIS]; + // auto wcos = parse_axes(value, wcos); continue; } if (tag == "Ov") { @@ -405,7 +405,7 @@ void OLED::parse_IP() { wrapped_draw_string(0, _radio_info, ArialMT_Plain_10); wrapped_draw_string(fh * 2, _radio_addr, ArialMT_Plain_10); _oled->display(); - delay_ms(_radio_delay); + delay_msec(_radio_delay); } // [MSG:INFO: AP SSID foo IP 192.168.68.134 mask foo channel foo] @@ -424,7 +424,7 @@ void OLED::parse_AP() { wrapped_draw_string(0, _radio_info, ArialMT_Plain_10); wrapped_draw_string(fh * 2, _radio_addr, ArialMT_Plain_10); _oled->display(); - delay_ms(_radio_delay); + delay_msec(_radio_delay); } void OLED::parse_BT() { @@ -436,7 +436,18 @@ void OLED::parse_BT() { _oled->clear(); wrapped_draw_string(0, _radio_info, ArialMT_Plain_10); _oled->display(); - delay_ms(_radio_delay); + delay_msec(_radio_delay); +} + +void OLED::parse_WebUI() { + size_t start = strlen("[MSG:INFO: WebUI: Request from "); + std::string ipaddr = _report.substr(start, _report.size() - start - 1); + + _oled->clear(); + auto fh = font_height(ArialMT_Plain_10); + wrapped_draw_string(0, "WebUI from", ArialMT_Plain_10); + wrapped_draw_string(fh * 2, ipaddr, ArialMT_Plain_10); + _oled->display(); } void OLED::parse_report() { @@ -467,6 +478,10 @@ void OLED::parse_report() { parse_BT(); return; } + if (_report.rfind("[MSG:INFO: WebUI: Request from ", 0) == 0) { + parse_WebUI(); + return; + } } // This is how the OLED driver receives channel data diff --git a/FluidNC/src/OLED.h b/FluidNC/src/OLED.h index c9937ba89..82530ed82 100644 --- a/FluidNC/src/OLED.h +++ b/FluidNC/src/OLED.h @@ -41,7 +41,8 @@ class OLED : public Channel, public Configuration::Configurable { float _percent; std::string _ticker; - int _radio_delay = 0; + int _radio_delay = 0; + int _report_interval_ms = 500; uint8_t _i2c_num = 0; @@ -52,9 +53,10 @@ class OLED : public Channel, public Configuration::Configurable { void parse_IP(); void parse_AP(); void parse_BT(); + void parse_WebUI(); - float* parse_axes(std::string s); - void parse_numbers(std::string s, float* nums, int maxnums); + void parse_axes(std::string s, float* axes); + void parse_numbers(std::string s, float* nums, int maxnums); void show_limits(bool probe, const bool* limits); void show_state(); @@ -115,6 +117,7 @@ class OLED : public Channel, public Configuration::Configurable { void afterParse() override; void group(Configuration::HandlerBase& handler) override { + handler.item("report_interval_ms", _report_interval_ms, 100, 5000); handler.item("i2c_num", _i2c_num); handler.item("i2c_address", _address); handler.item("width", _width); diff --git a/FluidNC/src/Parking.cpp b/FluidNC/src/Parking.cpp index 2eaf390a6..a5f7584fb 100644 --- a/FluidNC/src/Parking.cpp +++ b/FluidNC/src/Parking.cpp @@ -64,6 +64,7 @@ void Parking::setup() { plan_data.motion.systemMotion = 1; plan_data.motion.noFeedOverride = 1; plan_data.line_number = PARKING_MOTION_LINE_NUMBER; + plan_data.is_jog = false; block = plan_get_current_block(); if (block) { diff --git a/FluidNC/src/Pin.cpp b/FluidNC/src/Pin.cpp index 4cd075d61..a47cecbcd 100644 --- a/FluidNC/src/Pin.cpp +++ b/FluidNC/src/Pin.cpp @@ -1,4 +1,5 @@ // Copyright (c) 2021 - Stefan de Bruijn +// Copyright (c) 2023 - Dylan Knutson // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #include "Pin.h" @@ -9,94 +10,117 @@ #include "Pins/GPIOPinDetail.h" #include "Pins/VoidPinDetail.h" #include "Pins/I2SOPinDetail.h" +#include "Pins/ChannelPinDetail.h" #include "Pins/ErrorPinDetail.h" -#include // snprintf() +#include "string_util.h" +#include "Machine/MachineConfig.h" // config +#include +#include Pins::PinDetail* Pin::undefinedPin = new Pins::VoidPinDetail(); Pins::PinDetail* Pin::errorPin = new Pins::ErrorPinDetail("unknown"); -const char* Pin::parse(StringRange tmp, Pins::PinDetail*& pinImplementation) { - // Initialize pinImplementation first! Callers might want to delete it, and we don't want a random pointer. - pinImplementation = nullptr; +static constexpr bool verbose_debugging = false; - // Parse the definition: [GPIO].[pinNumber]:[attributes] +const char* Pin::parse(std::string_view pin_str, Pins::PinDetail*& pinImplementation) { + if (verbose_debugging) { + log_info("Parsing pin string: " << pin_str); + } - const char* end = tmp.end(); + // Initialize pinImplementation first! Callers might want to delete it, and we don't want a random pointer. + pinImplementation = nullptr; // Skip whitespaces at the start - auto nameStart = tmp.begin(); - for (; nameStart != end && ::isspace(*nameStart); ++nameStart) {} + pin_str = string_util::trim(pin_str); - if (nameStart == end) { + if (pin_str.empty()) { // Re-use undefined pins happens in 'create': - pinImplementation = new Pins::VoidPinDetail(); + pinImplementation = undefinedPin; return nullptr; } - auto idx = nameStart; - for (; idx != end && *idx != '.' && *idx != ':'; ++idx) {} - - StringRange prefix(tmp.begin(), idx); - - if (idx != end) { // skip '.' - ++idx; + auto dot_idx = pin_str.find('.'); + std::string_view prefix = pin_str.substr(0, dot_idx); + if (dot_idx != std::string::npos) { + dot_idx += 1; } + pin_str.remove_prefix(dot_idx); - int pinNumber = 0; - if (prefix != "") { - if (idx != end) { - for (int n = 0; idx != end && n <= 4 && *idx >= '0' && *idx <= '9'; ++idx, ++n) { - pinNumber = pinNumber * 10 + int(*idx - '0'); - } - } + if (verbose_debugging) { + log_info("Parsed pin prefix: " << prefix << ", rest: " << pin_str); } - while (idx != end && ::isspace(*idx)) { - ++idx; + char* pin_number_end = nullptr; + uint32_t pin_number = std::strtoul(pin_str.cbegin(), &pin_number_end, 10); + pin_str.remove_prefix(pin_number_end - pin_str.cbegin()); + + if (verbose_debugging) { + log_info("Parsed pin number: " << pin_number << ", rest: " << pin_str); } - if (idx != end) { - if (*idx != ':') { - // Pin definition attributes or EOF expected. - return "Pin attributes (':') were expected."; + if (!pin_str.empty() && pin_str[0] == ':') { + pin_str.remove_prefix(1); + if (pin_str.empty()) { + return "Pin attributes after ':' were expected."; } - ++idx; + } + + if (verbose_debugging) { + log_info("Remaining pin options: " << pin_str); } // Build an options parser: - Pins::PinOptionsParser parser(idx, end); + Pins::PinOptionsParser parser(pin_str.cbegin(), pin_str.cend()); // Build this pin: - if (prefix == "gpio") { - pinImplementation = new Pins::GPIOPinDetail(pinnum_t(pinNumber), parser); + if (string_util::equal_ignore_case(prefix, "gpio")) { + pinImplementation = new Pins::GPIOPinDetail(static_cast(pin_number), parser); + return nullptr; } -#ifdef ESP32 - if (prefix == "i2so") { - pinImplementation = new Pins::I2SOPinDetail(pinnum_t(pinNumber), parser); + if (string_util::equal_ignore_case(prefix, "i2so")) { + pinImplementation = new Pins::I2SOPinDetail(static_cast(pin_number), parser); + return nullptr; } -#endif - if (prefix == "no_pin") { + + if (string_util::starts_with_ignore_case(prefix, "uart_channel")) { + auto num_str = prefix.substr(strlen("uart_channel")); + int channel_num = -1; + std::from_chars(num_str.data(), num_str.data() + num_str.size(), channel_num); + if (channel_num == -1 || channel_num > 2) { + return "Bad uart_channel number"; + } + if (config->_uart_channels[channel_num] == nullptr) { + return "uart_channel is not configured"; + } + + pinImplementation = new Pins::ChannelPinDetail(config->_uart_channels[channel_num], pin_number, parser); + return nullptr; + } + + if (string_util::equal_ignore_case(prefix, "no_pin")) { pinImplementation = undefinedPin; + return nullptr; } - if (prefix == "void") { + if (string_util::equal_ignore_case(prefix, "void")) { // Note: having multiple void pins has its uses for debugging. pinImplementation = new Pins::VoidPinDetail(); + return nullptr; } if (pinImplementation == nullptr) { log_error("Unknown prefix:" << prefix); return "Unknown pin prefix"; - } else { + } #ifdef DEBUG_PIN_DUMP - pinImplementation = new Pins::DebugPinDetail(pinImplementation); + pinImplementation = new Pins::DebugPinDetail(pinImplementation); + return nullptr; +#else + return "Unknown pin prefix"; #endif - - return nullptr; - } } -Pin Pin::create(const StringRange& str) { +Pin Pin::create(std::string_view str) { Pins::PinDetail* pinImplementation = nullptr; try { const char* err = parse(str, pinImplementation); @@ -105,23 +129,15 @@ Pin Pin::create(const StringRange& str) { delete pinImplementation; } - log_error("Setting up pin:" << str.str() << " failed:" << err); - return Pin(new Pins::ErrorPinDetail(str.str().c_str())); + log_error("Setting up pin: " << str << " failed:" << err); + return Pin(new Pins::ErrorPinDetail(str)); } else { return Pin(pinImplementation); } } catch (const AssertionFailed& ex) { // We shouldn't get here under normal circumstances. - - char buf[255]; - snprintf(buf, 255, "ERR: %s - %s", str.str().c_str(), ex.what()); - - Assert(false, buf); - - /* - log_error("ERR: " << str.str() << " - " << ex.what()); - - return Pin(new Pins::ErrorPinDetail(str.str())); - */ + log_error("ERR: " << str << " - " << ex.what()); + Assert(false, ""); + // return Pin(new Pins::ErrorPinDetail(str.str())); } } diff --git a/FluidNC/src/Pin.h b/FluidNC/src/Pin.h index e40e38d4e..a3cf11b5f 100644 --- a/FluidNC/src/Pin.h +++ b/FluidNC/src/Pin.h @@ -6,32 +6,18 @@ #include "Pins/PinDetail.h" #include "Pins/PinCapabilities.h" #include "Pins/PinAttributes.h" -#include "StringRange.h" +#include "src/Machine/EventPin.h" #include // IRAM_ATTR #include #include #include #include +#include #include "Assert.h" // #define DEBUG_PIN_DUMP // Pin debugging. WILL spam you with a lot of data! -// Yuck, yuck, yuck... apparently we can't create a template with an IRAM_ATTR, because GCC refuses to obide -// by the attributes. In other words, _all_ templates are out when using an ISR! This define makes an anonymous -// method in the class, which can be used to wrap a single function. It can then be used by running the attachInterrupt -// with ISRHandler. -// -// Usage: -// - In header file (private / protected members) or in cpp file in anonymous namespace (public members) -// CreateISRHandlerFor(LimitPin, handleISR); -// - When attaching an ISR: _pin.attachInterrupt(ISRHandler, EITHER_EDGE, this); -// -// I'd rather not use any defines, but templates... but apparently there's no choice here. Let's just make it as safe -// as possible... -#define CreateISRHandlerFor(className, methodName) \ - static void IRAM_ATTR ISRHandler(void* data) { static_cast(data)->methodName(); } - // Pin class. A pin is basically a thing that can 'output', 'input' or do both. GPIO on an ESP32 comes to mind, // but there are way more possible pins. Think about I2S/I2C/SPI extenders, RS485 driven pin devices and even // WiFi wall sockets. @@ -77,7 +63,7 @@ class Pin { // Implementation details of this pin. Pins::PinDetail* _detail; - static const char* parse(StringRange str, Pins::PinDetail*& detail); + static const char* parse(std::string_view str, Pins::PinDetail*& detail); inline Pin(Pins::PinDetail* detail) : _detail(detail) {} @@ -99,10 +85,7 @@ class Pin { static const int ASSERTING = 0x10; static const int DEASSERTING = 0x11; - // inline static Pins::PinDetail* create(const char* str) { return create(StringRange(str)); }; - - static Pin create(const char* str) { return create(StringRange(str)); } // ensure it's not ambiguous - static Pin create(const StringRange& str); + static Pin create(std::string_view str); static bool validate(const char* str); // We delete the copy constructor, and implement the move constructor. The move constructor is required to support @@ -145,12 +128,7 @@ class Pin { static Pin Error() { return Pin(errorPin); } - // ISR handlers. Map methods on 'this' types. - - // Backward compatibility ISR handler: - void attachInterrupt(void (*callback)(void*), int mode, void* arg = nullptr) const { _detail->attachInterrupt(callback, arg, mode); } - - void detachInterrupt() const { _detail->detachInterrupt(); } + void registerEvent(EventPin* obj) { _detail->registerEvent(obj); }; // Other functions: Capabilities capabilities() const { return _detail->capabilities(); } diff --git a/FluidNC/src/Pins/ChannelPinDetail.cpp b/FluidNC/src/Pins/ChannelPinDetail.cpp new file mode 100644 index 000000000..ab5c60e69 --- /dev/null +++ b/FluidNC/src/Pins/ChannelPinDetail.cpp @@ -0,0 +1,82 @@ +// Copyright (c) 2023 - MitchBradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#include "ChannelPinDetail.h" + +namespace Pins { + ChannelPinDetail::ChannelPinDetail(Channel* channel, int number, const PinOptionsParser& options) : + PinDetail(number), _channel(channel) { + for (auto opt : options) { + if (opt.is("pu")) { + setAttr(PinAttributes::PullUp); + } else if (opt.is("pd")) { + setAttr(PinAttributes::PullDown); + } else if (opt.is("low")) { + setAttr(PinAttributes::ActiveLow); + } else if (opt.is("high")) { + // Default: Active HIGH. + } + } + } + + PinCapabilities ChannelPinDetail::capabilities() const { + return PinCapabilities::Output | PinCapabilities::Input | PinCapabilities::PWM | PinCapabilities::Void; + } + + void ChannelPinDetail::write(int high) { + if (high == _value) { + return; + } + _value = high; + std::string s = "SET: io."; + s += std::to_string(_index); + s += "="; + s += std::to_string(high); + _channel->out(s); + } + int ChannelPinDetail::read() { return _value; } + void ChannelPinDetail::setAttr(PinAttributes attr) { + _attributes = _attributes | attr; + + std::string s = "INI: io."; + s += std::to_string(_index); + s += "="; + if (_attributes.has(Pins::PinAttributes::Input)) { + s += "inp"; + } else if (_attributes.has(Pins::PinAttributes::Output)) { + s += "out"; + } else { + return; + } + + if (_attributes.has(Pins::PinAttributes::PullUp)) { + s += ":pu"; + } + if (_attributes.has(Pins::PinAttributes::PullDown)) { + s += ":pd"; + } + if (_attributes.has(Pins::PinAttributes::ActiveLow)) { + s += ":low"; + } + + _channel->setAttr(_index, _attributes.has(Pins::PinAttributes::Input) ? &this->_value : nullptr, s); + } + PinAttributes ChannelPinDetail::getAttr() const { return _attributes; } + std::string ChannelPinDetail::toString() { + std::string s = _channel->name(); + s += "."; + s += std::to_string(_index); + if (_attributes.has(PinAttributes::ActiveLow)) { + s += ":low"; + } + if (_attributes.has(PinAttributes::PullUp)) { + s += ":pu"; + } + if (_attributes.has(PinAttributes::PullDown)) { + s += ":pd"; + } + return s; + } + + void ChannelPinDetail::registerEvent(EventPin* obj) { _channel->registerEvent(_index, obj); } +} diff --git a/FluidNC/src/Pins/ChannelPinDetail.h b/FluidNC/src/Pins/ChannelPinDetail.h new file mode 100644 index 000000000..a460cfab0 --- /dev/null +++ b/FluidNC/src/Pins/ChannelPinDetail.h @@ -0,0 +1,35 @@ +// Copyright (c) 2023 - Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#pragma once + +#include "PinDetail.h" +#include "PinOptionsParser.h" +#include "src/Channel.h" +#include "../Logging.h" + +namespace Pins { + class ChannelPinDetail : public PinDetail { + private: + Channel* _channel; + PinAttributes _attributes; + bool _value = false; + + public: + ChannelPinDetail(Channel* channel, int number, const PinOptionsParser& options); + + PinCapabilities capabilities() const override; + + // I/O: + void write(int high) override; + int read() override; + void setAttr(PinAttributes value) override; + PinAttributes getAttr() const override; + + void registerEvent(EventPin* obj); + + std::string toString() override; + + ~ChannelPinDetail() override {} + }; +} diff --git a/FluidNC/src/Pins/DebugPinDetail.cpp b/FluidNC/src/Pins/DebugPinDetail.cpp index 63e72d236..d32f7f9f7 100644 --- a/FluidNC/src/Pins/DebugPinDetail.cpp +++ b/FluidNC/src/Pins/DebugPinDetail.cpp @@ -5,28 +5,15 @@ #include "../UartChannel.h" #include // millis() -#include // vsnprintf -#include namespace Pins { - inline void WriteSerial(const char* format, ...) { - char buf[50]; - va_list arg; - va_list copy; - va_start(arg, format); - va_copy(copy, arg); - size_t len = vsnprintf(buf, 50, format, arg); - va_end(copy); - log_msg_to(Uart0, buf); - va_end(arg); - } // I/O: void DebugPinDetail::write(int high) { if (high != int(_isHigh)) { _isHigh = bool(high); if (shouldEvent()) { - WriteSerial("Write %s < %d", toString(), high); + log_msg_to(Uart0, "Write " << toString() << " < " << high); } } _implementation->write(high); @@ -35,7 +22,7 @@ namespace Pins { int DebugPinDetail::read() { auto result = _implementation->read(); if (shouldEvent()) { - WriteSerial("Read %s > %d", toString(), result); + log_msg_to(Uart0, "Read " << toString() << " > " << result); } return result; } @@ -63,10 +50,10 @@ namespace Pins { if (value.has(PinAttributes::InitialOn)) { buf[n++] = '+'; } - buf[n++] = 0; + buf[n++] = '\0'; if (shouldEvent()) { - WriteSerial("Set pin attr %s = %s", toString(), buf); + log_msg_to(Uart0, "Set pin attr " << toString() << " = " << buf); } _implementation->setAttr(value); } @@ -76,44 +63,8 @@ namespace Pins { void DebugPinDetail::CallbackHandler::handle(void* arg) { auto handler = static_cast(arg); if (handler->_myPin->shouldEvent()) { - WriteSerial("Received ISR on %s", handler->_myPin->toString()); + log_msg_to(Uart0, "Received ISR on " << handler->_myPin->toString()); } handler->callback(handler->argument); } - - // ISR's: - void DebugPinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) { - _isrHandler._myPin = this; - _isrHandler.argument = arg; - _isrHandler.callback = callback; - - if (shouldEvent()) { - WriteSerial("Attaching interrupt to pin %s, mode %d", toString(), mode); - } - _implementation->attachInterrupt(_isrHandler.handle, &_isrHandler, mode); - } - void DebugPinDetail::detachInterrupt() { _implementation->detachInterrupt(); } - - bool DebugPinDetail::shouldEvent() { - // This method basically ensures we don't flood users: - auto time = millis(); - - if ((time - _lastEvent) > 1000) { - _lastEvent = time; - _eventCount = 1; - return true; - } else if (_eventCount < 10) { - _lastEvent = time; - ++_eventCount; - return true; - } else if (_eventCount == 10) { - _lastEvent = time; - ++_eventCount; - WriteSerial("Suppressing events..."); - return false; - } else { - _lastEvent = time; - return false; - } - } } diff --git a/FluidNC/src/Pins/DebugPinDetail.h b/FluidNC/src/Pins/DebugPinDetail.h index b6b10ff84..2b2616095 100644 --- a/FluidNC/src/Pins/DebugPinDetail.h +++ b/FluidNC/src/Pins/DebugPinDetail.h @@ -38,10 +38,6 @@ namespace Pins { void setAttr(PinAttributes value) override; PinAttributes getAttr() const override; - // ISR's: - void attachInterrupt(void (*callback)(void*), void* arg, int mode) override; - void detachInterrupt() override; - std::string toString() override { return _implementation->toString(); } ~DebugPinDetail() override {} diff --git a/FluidNC/src/Pins/ErrorPinDetail.cpp b/FluidNC/src/Pins/ErrorPinDetail.cpp index 996ebe342..32a390c43 100644 --- a/FluidNC/src/Pins/ErrorPinDetail.cpp +++ b/FluidNC/src/Pins/ErrorPinDetail.cpp @@ -6,7 +6,7 @@ #include "../Assert.h" namespace Pins { - ErrorPinDetail::ErrorPinDetail(const char* descr) : PinDetail(0), _description(descr) {} + ErrorPinDetail::ErrorPinDetail(std::string_view descr) : PinDetail(0), _description(descr) {} PinCapabilities ErrorPinDetail::capabilities() const { return PinCapabilities::Error; } diff --git a/FluidNC/src/Pins/ErrorPinDetail.h b/FluidNC/src/Pins/ErrorPinDetail.h index 68eea1cc0..6697531b2 100644 --- a/FluidNC/src/Pins/ErrorPinDetail.h +++ b/FluidNC/src/Pins/ErrorPinDetail.h @@ -5,13 +5,14 @@ #include "PinDetail.h" #include "PinOptionsParser.h" +#include namespace Pins { class ErrorPinDetail : public PinDetail { std::string _description; public: - ErrorPinDetail(const char* descr); + ErrorPinDetail(std::string_view descr); PinCapabilities capabilities() const override; diff --git a/FluidNC/src/Pins/GPIOPinDetail.cpp b/FluidNC/src/Pins/GPIOPinDetail.cpp index fa1c428d0..a1f136b5a 100644 --- a/FluidNC/src/Pins/GPIOPinDetail.cpp +++ b/FluidNC/src/Pins/GPIOPinDetail.cpp @@ -7,8 +7,9 @@ #include #include "GPIOPinDetail.h" -#include "../Assert.h" -#include "../Config.h" +#include "src/Assert.h" +#include "src/Config.h" +#include "src/Machine/EventPin.h" namespace Pins { std::vector GPIOPinDetail::_claimed(nGPIOPins, false); @@ -29,6 +30,8 @@ namespace Pins { PinCapabilities::UART; case 5: + case 9: + case 10: case 16: case 17: case 18: @@ -62,8 +65,6 @@ namespace Pins { case 6: // SPI flash integrated case 7: case 8: - case 9: - case 10: case 11: return PinCapabilities::Reserved; @@ -169,14 +170,15 @@ namespace Pins { false); // We do not have an OpenDrain attribute yet } - void GPIOPinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) { - Assert(_attributes.has(PinAttributes::ISR), "Pin %s does not support interrupts", toString().c_str()); - ::attachInterruptArg(_index, callback, arg, mode); + // This is a callback from the low-level GPIO driver that is invoked after + // registerEvent() has been called and the pin becomes active. + void GPIOPinDetail::gpioAction(int gpio_num, void* arg, bool active) { + EventPin* obj = static_cast(arg); + obj->trigger(active); } - void GPIOPinDetail::detachInterrupt() { - Assert(_attributes.has(PinAttributes::ISR), "Pin %s does not support interrupts"); - ::detachInterrupt(_index); + void GPIOPinDetail::registerEvent(EventPin* obj) { + gpio_set_action(_index, gpioAction, (void*)obj, _attributes.has(Pin::Attr::ActiveLow)); } std::string GPIOPinDetail::toString() { diff --git a/FluidNC/src/Pins/GPIOPinDetail.h b/FluidNC/src/Pins/GPIOPinDetail.h index c4f04ef53..68dbdee0b 100644 --- a/FluidNC/src/Pins/GPIOPinDetail.h +++ b/FluidNC/src/Pins/GPIOPinDetail.h @@ -17,6 +17,8 @@ namespace Pins { bool _lastWrittenValue = false; + static void gpioAction(int, void*, bool); + public: static const int nGPIOPins = 40; @@ -30,9 +32,7 @@ namespace Pins { void setAttr(PinAttributes value) override; PinAttributes getAttr() const override; - // ISR's: - void attachInterrupt(void (*callback)(void*), void* arg, int mode) override; - void detachInterrupt() override; + void registerEvent(EventPin* obj) override; std::string toString() override; diff --git a/FluidNC/src/Pins/PinAttributes.h b/FluidNC/src/Pins/PinAttributes.h index 30d5b6617..abe3a43b6 100644 --- a/FluidNC/src/Pins/PinAttributes.h +++ b/FluidNC/src/Pins/PinAttributes.h @@ -23,6 +23,9 @@ namespace Pins { constexpr PinAttributes(const uint32_t value) : _value(value) {} public: + // Having a default constructor lets us use PinAttributes with std::map + PinAttributes() { _value = Undefined; } + PinAttributes(const PinAttributes&) = default; PinAttributes& operator=(const PinAttributes&) = default; diff --git a/FluidNC/src/Pins/PinCapabilities.cpp b/FluidNC/src/Pins/PinCapabilities.cpp index 1b8c6d0cf..3e54bb00a 100644 --- a/FluidNC/src/Pins/PinCapabilities.cpp +++ b/FluidNC/src/Pins/PinCapabilities.cpp @@ -29,6 +29,7 @@ namespace Pins { PinCapabilities PinCapabilities::Native(1 << (__LINE__ - START_LINE)); PinCapabilities PinCapabilities::I2S(1 << (__LINE__ - START_LINE)); + PinCapabilities PinCapabilities::UARTIO(1 << (__LINE__ - START_LINE)); PinCapabilities PinCapabilities::Error(1 << (__LINE__ - START_LINE)); PinCapabilities PinCapabilities::Void(1 << (__LINE__ - START_LINE)); } diff --git a/FluidNC/src/Pins/PinCapabilities.h b/FluidNC/src/Pins/PinCapabilities.h index ea9849d2c..f457115f1 100644 --- a/FluidNC/src/Pins/PinCapabilities.h +++ b/FluidNC/src/Pins/PinCapabilities.h @@ -21,7 +21,7 @@ namespace Pins { friend class PinAttributes; // Wants access to _value for validation public: - PinCapabilities(const PinCapabilities&) = default; + PinCapabilities(const PinCapabilities&) = default; PinCapabilities& operator=(const PinCapabilities&) = default; // All the capabilities we use and test: @@ -44,6 +44,7 @@ namespace Pins { // can compare classes of pins along with their properties by just looking at the capabilities. static PinCapabilities Native; static PinCapabilities I2S; + static PinCapabilities UARTIO; static PinCapabilities Error; static PinCapabilities Void; diff --git a/FluidNC/src/Pins/PinDetail.cpp b/FluidNC/src/Pins/PinDetail.cpp index d2348af7a..9b41dc30a 100644 --- a/FluidNC/src/Pins/PinDetail.cpp +++ b/FluidNC/src/Pins/PinDetail.cpp @@ -7,13 +7,8 @@ #include // IRAM_ATTR namespace Pins { - void PinDetail::attachInterrupt(void (*callback)(void*), void* arg, int mode) { - Assert(false, "Interrupts are not supported by pin %d", _index); - } - void PinDetail::detachInterrupt() { - Assert(false, "Interrupts are not supported by pin %d", _index); - ; - } + void PinDetail::registerEvent(EventPin* obj) { Assert(false, "registerEvent is not supported by pin %d", _index); } + void IRAM_ATTR PinDetail::synchronousWrite(int high) { write(high); } } diff --git a/FluidNC/src/Pins/PinDetail.h b/FluidNC/src/Pins/PinDetail.h index c0cf4cccb..ecfc77bc7 100644 --- a/FluidNC/src/Pins/PinDetail.h +++ b/FluidNC/src/Pins/PinDetail.h @@ -6,6 +6,7 @@ #include "PinCapabilities.h" #include "PinAttributes.h" #include "PinOptionsParser.h" +#include "src/Machine/EventPin.h" #include #include @@ -37,9 +38,7 @@ namespace Pins { virtual void setAttr(PinAttributes value) = 0; virtual PinAttributes getAttr() const = 0; - // ISR's. - virtual void attachInterrupt(void (*callback)(void*), void* arg, int mode); - virtual void detachInterrupt(); + virtual void registerEvent(EventPin* obj); virtual std::string toString() = 0; diff --git a/FluidNC/src/Pins/PinOptionsParser.h b/FluidNC/src/Pins/PinOptionsParser.h index 73c430477..46d7c288b 100644 --- a/FluidNC/src/Pins/PinOptionsParser.h +++ b/FluidNC/src/Pins/PinOptionsParser.h @@ -3,8 +3,6 @@ #pragma once -class Pin; // Forward declaration - namespace Pins { // Pin options are passed as PinOption object. This is a simple C++ forward iterator, // which will implicitly convert pin options to lower case, so you can simply do diff --git a/FluidNC/src/Planner.cpp b/FluidNC/src/Planner.cpp index e42e2834f..c0b717448 100644 --- a/FluidNC/src/Planner.cpp +++ b/FluidNC/src/Planner.cpp @@ -306,8 +306,16 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) { int32_t target_steps[MAX_N_AXIS], position_steps[MAX_N_AXIS]; float unit_vec[MAX_N_AXIS], delta_mm; // Copy position data based on type of motion being planned. - copyAxes(position_steps, block->motion.systemMotion ? get_motor_steps() : pl.position); - + if (block->motion.systemMotion) { + copyAxes(position_steps, get_motor_steps()); + } else { + if (!block->is_jog && Homing::unhomed_axes()) { + log_info("Unhomed axes: " << config->_axes->maskToNames(Homing::unhomed_axes())); + send_alarm(ExecAlarm::Unhomed); + return false; + } + copyAxes(position_steps, pl.position); + } auto n_axis = config->_axes->_numberAxis; for (size_t idx = 0; idx < n_axis; idx++) { // Calculate target position in absolute steps, number of steps for each axis, and determine max step events. diff --git a/FluidNC/src/Planner.h b/FluidNC/src/Planner.h index 684c3104f..888999734 100644 --- a/FluidNC/src/Planner.h +++ b/FluidNC/src/Planner.h @@ -12,6 +12,7 @@ #include "Config.h" // MAX_N_AXIS #include "SpindleDatatypes.h" // SpindleState #include "GCode.h" // CoolantState +#include "Types.h" // AxisMask #include @@ -61,13 +62,14 @@ struct plan_block_t { // Planner data prototype. Must be used when passing new motions to the planner. struct plan_line_data_t { - float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion. - SpindleSpeed spindle_speed; // Desired spindle speed through line motion. - PlMotion motion; // Bitflag variable to indicate motion conditions. See defines above. - SpindleState spindle; // Spindle enable state - CoolantState coolant; // Coolant state - int32_t line_number; // Desired line number to report when executing. - bool is_jog; // true if this was generated due to a jog command + float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion. + SpindleSpeed spindle_speed; // Desired spindle speed through line motion. + PlMotion motion; // Bitflag variable to indicate motion conditions. See defines above. + SpindleState spindle; // Spindle enable state + CoolantState coolant; // Coolant state + int32_t line_number; // Desired line number to report when executing. + bool is_jog; // true if this was generated due to a jog command + bool limits_checked; // true if soft limits already checked }; void plan_init(); diff --git a/FluidNC/src/Probe.cpp b/FluidNC/src/Probe.cpp index 0017cb70c..833e3b65c 100644 --- a/FluidNC/src/Probe.cpp +++ b/FluidNC/src/Probe.cpp @@ -11,6 +11,7 @@ void Probe::init() { static bool show_init_msg = true; // used to show message only once. if (_probePin.defined()) { + _probePin.getNative(Pin::Capabilities::Input | Pin::Capabilities::Native); _probePin.setAttr(Pin::Attr::Input); if (show_init_msg) { @@ -18,6 +19,16 @@ void Probe::init() { show_init_msg = false; } } + + if (_toolsetter_Pin.defined()) { + _toolsetter_Pin.getNative(Pin::Capabilities::Input | Pin::Capabilities::Native); + _toolsetter_Pin.setAttr(Pin::Attr::Input); + + if (show_init_msg) { + _toolsetter_Pin.report("Toolsetter Pin:"); + } + } + show_init_msg = false; } void Probe::set_direction(bool is_away) { @@ -26,19 +37,20 @@ void Probe::set_direction(bool is_away) { // Returns the probe pin state. Triggered = true. Called by gcode parser. bool Probe::get_state() { - return _probePin.read(); + return (_probePin.read() || _toolsetter_Pin.read()); } // Returns true if the probe pin is tripped, accounting for the direction (away or not). // This function must be extremely efficient as to not bog down the stepper ISR. // Should be called only in situations where the probe pin is known to be defined. bool IRAM_ATTR Probe::tripped() { - return _probePin.read() ^ _isProbeAway; + return (_probePin.read() || _toolsetter_Pin.read()) ^ _isProbeAway; } void Probe::validate() {} void Probe::group(Configuration::HandlerBase& handler) { handler.item("pin", _probePin); + handler.item("toolsetter_pin", _toolsetter_Pin); handler.item("check_mode_start", _check_mode_start); } diff --git a/FluidNC/src/Probe.h b/FluidNC/src/Probe.h index 14c5176c2..cfa32681d 100644 --- a/FluidNC/src/Probe.h +++ b/FluidNC/src/Probe.h @@ -21,6 +21,7 @@ class Probe : public Configuration::Configurable { // Configurable Pin _probePin; + Pin _toolsetter_Pin; public: // Configurable @@ -31,8 +32,7 @@ class Probe : public Configuration::Configurable { Probe() = default; - bool exists() const { return _probePin.defined(); } - + bool exists() const { return _probePin.defined() || _toolsetter_Pin.defined(); } // Probe pin initialization routine. void init(); diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index 892293d18..21bc7c367 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -25,6 +25,7 @@ #include "Driver/fluidnc_gpio.h" // gpio_dump() #include "FluidPath.h" +#include "HashFS.h" #include #include @@ -34,6 +35,8 @@ // WU Readable and writable as user and admin // WA Readable as user and admin, writable as admin +static Error fakeMaxSpindleSpeed(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out); + // If authentication is disabled, auth_level will be LEVEL_ADMIN static bool auth_failed(Word* w, const char* value, WebUI::AuthenticationLevel auth_level) { permissions_t permissions = w->getPermissions(); @@ -132,7 +135,7 @@ void settings_restore(uint8_t restore_flag) { if (restore_flag & SettingsRestore::Defaults) { bool restore_startup = restore_flag & SettingsRestore::StartupLines; - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { if (!s->getDescription()) { const char* name = s->getName(); if (restore_startup) { // all settings get restored @@ -156,7 +159,7 @@ void settings_restore(uint8_t restore_flag) { // Get settings values from non volatile storage into memory static void load_settings() { - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { s->load(); } } @@ -185,20 +188,22 @@ static Error report_gcode(const char* value, WebUI::AuthenticationLevel auth_lev } static void show_settings(Channel& out, type_t type) { - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { if (s->getType() == type && s->getGrblName()) { // The following test could be expressed more succinctly with XOR, // but is arguably clearer when written out show_setting(s->getGrblName(), s->getCompatibleValue(), NULL, out); } } + // need this per issue #1036 + fakeMaxSpindleSpeed(NULL, WebUI::AuthenticationLevel::LEVEL_ADMIN, out); } static Error report_normal_settings(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { show_settings(out, GRBL); // GRBL non-axis settings return Error::Ok; } static Error list_grbl_names(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { - for (Setting* setting = Setting::List; setting; setting = setting->next()) { + for (Setting* setting : Setting::List) { const char* gn = setting->getGrblName(); if (gn) { log_to(out, "$", gn << " => $" << setting->getName()); @@ -207,7 +212,7 @@ static Error list_grbl_names(const char* value, WebUI::AuthenticationLevel auth_ return Error::Ok; } static Error list_settings(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { const char* displayValue = auth_failed(s, value, auth_level) ? "" : s->getStringValue(); if (s->getType() != PIN) { show_setting(s->getName(), displayValue, NULL, out); @@ -216,7 +221,7 @@ static Error list_settings(const char* value, WebUI::AuthenticationLevel auth_le return Error::Ok; } static Error list_changed_settings(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { const char* value = s->getStringValue(); if (!auth_failed(s, value, auth_level) && strcmp(value, s->getDefaultString())) { if (s->getType() != PIN) { @@ -228,7 +233,7 @@ static Error list_changed_settings(const char* value, WebUI::AuthenticationLevel return Error::Ok; } static Error list_commands(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { - for (Command* cp = Command::List; cp; cp = cp->next()) { + for (Command* cp : Command::List) { const char* name = cp->getName(); const char* oldName = cp->getGrblName(); LogStream s(out, "$"); @@ -252,9 +257,8 @@ static Error toggle_check_mode(const char* value, WebUI::AuthenticationLevel aut // idle and ready, regardless of alarm locks. This is mainly to keep things // simple and consistent. if (sys.state == State::CheckMode) { - log_debug("Check mode"); - mc_reset(); report_feedback_message(Message::Disabled); + sys.abort = true; } else { if (sys.state != State::Idle) { return Error::IdleError; // Requires no alarm mode. @@ -267,12 +271,12 @@ static Error toggle_check_mode(const char* value, WebUI::AuthenticationLevel aut static Error isStuck() { // Block if a control pin is stuck on if (config->_control->safety_door_ajar()) { - rtAlarm = ExecAlarm::ControlPin; + send_alarm(ExecAlarm::ControlPin); return Error::CheckDoor; } if (config->_control->stuck()) { log_info("Control pins:" << config->_control->report_status()); - rtAlarm = ExecAlarm::ControlPin; + send_alarm(ExecAlarm::ControlPin); return Error::CheckControlPins; } return Error::Ok; @@ -286,17 +290,93 @@ static Error disable_alarm_lock(const char* value, WebUI::AuthenticationLevel au if (err != Error::Ok) { return err; } + Homing::set_all_axes_homed(); report_feedback_message(Message::AlarmUnlock); sys.state = State::Idle; - - // Don't run startup script. Prevents stored moves in startup from causing accidents. - } // Otherwise, no effect. + } + // Run the after_unlock macro even if no unlock was necessary + config->_macros->_after_unlock.run(); return Error::Ok; } static Error report_ngc(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { report_ngc_parameters(out); return Error::Ok; } +static Error msg_to_uart0(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + Channel* dest = allChannels.find("uart_channel0"); + if (dest) { + log_msg_to(*dest, value); + } + } + return Error::Ok; +} +static Error msg_to_uart1(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value && config->_uart_channels[1]) { + log_msg_to(*(config->_uart_channels[1]), value); + } + return Error::Ok; +} +static Error cmd_log_msg(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + if (*value == '*') { + log_msg(value + 1); + } else { + log_msg_to(out, value); + } + } + return Error::Ok; +} +static Error cmd_log_error(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + if (*value == '*') { + log_error(value + 1); + } else { + log_error_to(out, value); + } + } + return Error::Ok; +} +static Error cmd_log_warn(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + if (*value == '*') { + log_warn(value + 1); + } else { + log_warn_to(out, value); + } + } + return Error::Ok; +} +static Error cmd_log_info(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + if (*value == '*') { + log_info(value + 1); + } else { + log_info_to(out, value); + } + } + return Error::Ok; +} +static Error cmd_log_debug(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + if (*value == '*') { + log_debug(value + 1); + } else { + log_debug_to(out, value); + } + } + return Error::Ok; +} +static Error cmd_log_verbose(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + if (*value == '*') { + log_verbose(value + 1); + } else { + log_verbose_to(out, value); + } + } + return Error::Ok; +} static Error home(AxisMask axisMask) { if (axisMask != Machine::Homing::AllCycles) { // if not AllCycles we need to make sure the cycle is not prohibited // if there is a cycle it is the axis from $H @@ -328,7 +408,9 @@ static Error home(AxisMask axisMask) { protocol_execute_realtime(); } while (sys.state == State::Homing); - settings_execute_startup(); + if (!Homing::unhomed_axes()) { + config->_macros->_after_homing.run(); + } return Error::Ok; } @@ -439,9 +521,9 @@ static Error get_report_build_info(const char* value, WebUI::AuthenticationLevel } return Error::InvalidStatement; } -static Error report_startup_lines(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { +static Error show_startup_lines(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { for (int i = 0; i < config->_macros->n_startup_lines; i++) { - log_to(out, "$N", i << "=" << config->_macros->startup_line(i)); + log_to(out, "$N", i << "=" << config->_macros->_startup_line[i]._gcode); } return Error::Ok; } @@ -492,16 +574,11 @@ static Error doJog(const char* value, WebUI::AuthenticationLevel auth_level, Cha return gc_execute_line(jogLine); } -static const char* alarmString(ExecAlarm alarmNumber) { - auto it = AlarmNames.find(alarmNumber); - return it == AlarmNames.end() ? NULL : it->second; -} - static Error listAlarms(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { if (sys.state == State::ConfigAlarm) { log_to(out, "Configuration alarm is active. Check the boot messages for 'ERR'."); - } else if (rtAlarm != ExecAlarm::None) { - log_to(out, "Active alarm: ", int(rtAlarm) << " (" << alarmString(rtAlarm)); + } else if (sys.state == State::Alarm) { + log_to(out, "Active alarm: ", int(lastAlarm) << " (" << alarmString(lastAlarm)); } if (value) { char* endptr = NULL; @@ -601,9 +678,9 @@ static Error motors_init(const char* value, WebUI::AuthenticationLevel auth_leve static Error macros_run(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { if (value) { - log_info("Running macro " << *value); + log_info("Running macro" << *value); size_t macro_num = (*value) - '0'; - config->_macros->run_macro(macro_num); + config->_macros->_macro[macro_num].run(); return Error::Ok; } log_error("$Macros/Run requires a macro number argument"); @@ -634,7 +711,10 @@ static Error xmodem_receive(const char* value, WebUI::AuthenticationLevel auth_l } else { log_info("Reception failed or was canceled"); } + std::filesystem::path fname = outfile->fpath(); delete outfile; + HashFS::rehash_file(fname); + return size < 0 ? Error::UploadFailed : Error::Ok; } @@ -688,7 +768,7 @@ static Error dump_config(const char* value, WebUI::AuthenticationLevel auth_leve static Error fakeMaxSpindleSpeed(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { if (!value) { - log_to(out, "$30=", spindle->maxSpeed()) + log_to(out, "$30=", spindle->maxSpeed()); } return Error::Ok; } @@ -706,7 +786,7 @@ static Error showChannelInfo(const char* value, WebUI::AuthenticationLevel auth_ } static Error showStartupLog(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { - startupLog.dump(out); + StartupLog::dump(out); return Error::Ok; } @@ -748,6 +828,11 @@ static Error setReportInterval(const char* value, WebUI::AuthenticationLevel aut return Error::Ok; } +static Error showHeap(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + log_info("Heap free: " << xPortGetFreeHeapSize() << " min: " << heapLowWater); + 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 @@ -758,7 +843,7 @@ void make_user_commands() { new UserCommand("CI", "Channel/Info", showChannelInfo, anyState); new UserCommand("XR", "Xmodem/Receive", xmodem_receive, notIdleOrAlarm); - new UserCommand("XS", "Xmodem/Send", xmodem_send, notIdleOrJog); + new UserCommand("XS", "Xmodem/Send", xmodem_send, notIdleOrAlarm); new UserCommand("CD", "Config/Dump", dump_config, anyState); new UserCommand("", "Help", show_help, anyState); new UserCommand("T", "State", showState, anyState); @@ -792,11 +877,21 @@ void make_user_commands() { new UserCommand("HB", "Home/B", home_b, notIdleOrAlarm); new UserCommand("HC", "Home/C", home_c, notIdleOrAlarm); + new UserCommand("MU0", "Msg/Uart0", msg_to_uart0, anyState); + new UserCommand("MU1", "Msg/Uart1", msg_to_uart1, anyState); + new UserCommand("LM", "Log/Msg", cmd_log_msg, anyState); + new UserCommand("LE", "Log/Error", cmd_log_error, anyState); + new UserCommand("LW", "Log/Warn", cmd_log_warn, anyState); + new UserCommand("LI", "Log/Info", cmd_log_info, anyState); + new UserCommand("LD", "Log/Debug", cmd_log_debug, anyState); + new UserCommand("LV ", "Log/Verbose", cmd_log_verbose, anyState); + new UserCommand("SLP", "System/Sleep", go_to_sleep, notIdleOrAlarm); new UserCommand("I", "Build/Info", get_report_build_info, notIdleOrAlarm); - new UserCommand("N", "GCode/StartupLines", report_startup_lines, notIdleOrAlarm); + new UserCommand("N", "GCode/StartupLines", show_startup_lines, notIdleOrAlarm); new UserCommand("RST", "Settings/Restore", restore_settings, notIdleOrAlarm, WA); + new UserCommand("Heap", "Heap/Show", showHeap, anyState); new UserCommand("SS", "Startup/Show", showStartupLog, anyState); new UserCommand("RI", "Report/Interval", setReportInterval, anyState); @@ -880,7 +975,7 @@ Error do_command_or_setting(const char* key, char* value, WebUI::AuthenticationL // Next search the settings list by text name. If found, set a new // value if one is given, otherwise display the current value - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { if (strcasecmp(s->getName(), key) == 0) { if (auth_failed(s, value, auth_level)) { return Error::AuthenticationFailed; @@ -896,7 +991,7 @@ Error do_command_or_setting(const char* key, char* value, WebUI::AuthenticationL // Then search the setting list by compatible name. If found, set a new // value if one is given, otherwise display the current value in compatible mode - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { if (s->getGrblName() && strcasecmp(s->getGrblName(), key) == 0) { if (auth_failed(s, value, auth_level)) { return Error::AuthenticationFailed; @@ -912,7 +1007,7 @@ Error do_command_or_setting(const char* key, char* value, WebUI::AuthenticationL // If we did not find a setting, look for a command. Commands // handle values internally; you cannot determine whether to set // or display solely based on the presence of a value. - for (Command* cp = Command::List; cp; cp = cp->next()) { + for (Command* cp : Command::List) { if ((strcasecmp(cp->getName(), key) == 0) || (cp->getGrblName() && strcasecmp(cp->getGrblName(), key) == 0)) { if (auth_failed(cp, value, auth_level)) { return Error::AuthenticationFailed; @@ -928,7 +1023,7 @@ Error do_command_or_setting(const char* key, char* value, WebUI::AuthenticationL Error retval = Error::InvalidStatement; if (!value) { bool found = false; - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { auto test = s->getName(); // The C++ standard regular expression library supports many more // regular expression forms than the simple one in Regex.cpp, but @@ -983,20 +1078,12 @@ Error settings_execute_line(char* line, Channel& out, WebUI::AuthenticationLevel } void settings_execute_startup() { + if (sys.state != State::Idle) { + return; + } Error status_code; for (int i = 0; i < config->_macros->n_startup_lines; i++) { - auto str = config->_macros->startup_line(i); - if (str.length()) { - // We have to copy this to a mutable array because - // gc_execute_line modifies the line while parsing. - char gcline[256]; - strncpy(gcline, str.c_str(), 255); - status_code = gc_execute_line(gcline); - // Uart0 << ">" << gcline << ":"; - if (status_code != Error::Ok) { - log_error("Startup line: " << errorString(status_code)); - } - } + config->_macros->_startup_line[i].run(); } } diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 3937c9c6d..7fc6dec19 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -19,7 +19,7 @@ #include "Settings.h" // settings_execute_startup #include "Machine/LimitPin.h" -volatile ExecAlarm rtAlarm; // Global realtime executor bitflag variable for setting various alarms. +volatile ExecAlarm lastAlarm; // The most recent alarm code std::map AlarmNames = { { ExecAlarm::None, "None" }, @@ -35,9 +35,15 @@ std::map AlarmNames = { { ExecAlarm::SpindleControl, "Spindle Control" }, { ExecAlarm::ControlPin, "Control Pin Initially On" }, { ExecAlarm::HomingAmbiguousSwitch, "Ambiguous Switch" }, + { ExecAlarm::HardStop, "Hard Stop" }, + { ExecAlarm::Unhomed, "Unhomed" }, + { ExecAlarm::Init, "Init" }, }; -volatile bool rtReset; +const char* alarmString(ExecAlarm alarmNumber) { + auto it = AlarmNames.find(alarmNumber); + return it == AlarmNames.end() ? NULL : it->second; +} static volatile bool rtSafetyDoor; @@ -68,12 +74,8 @@ static SpindleStop spindle_stop_ovr; void protocol_reset() { probeState = ProbeState::Off; soft_limit = false; - rtReset = false; rtSafetyDoor = false; 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; @@ -92,6 +94,7 @@ xQueueHandle message_queue; struct LogMessage { Channel* channel; void* line; + MsgLevel level; bool isString; }; @@ -106,12 +109,12 @@ void drain_messages() { // memory does not need to be reclaimed later. // This is the most efficient form, but it only works // with fixed messages. -void send_line(Channel& channel, const char* line) { +void send_line(Channel& channel, MsgLevel level, const char* line) { if (outputTask) { - LogMessage msg { &channel, (void*)line, false }; + LogMessage msg { &channel, (void*)line, level, false }; while (!xQueueSend(message_queue, &msg, 10)) {} } else { - channel.println(line); + channel.print_msg(level, line); } } @@ -123,12 +126,12 @@ void send_line(Channel& channel, const char* line) { // the pointer to reclaim the memory. // This form has intermediate efficiency, as the string // is allocated once and freed once. -void send_line(Channel& channel, const std::string* line) { +void send_line(Channel& channel, MsgLevel level, const std::string* line) { if (outputTask) { - LogMessage msg { &channel, (void*)line, true }; + LogMessage msg { &channel, (void*)line, level, true }; while (!xQueueSend(message_queue, &msg, 10)) {} } else { - channel.println(line->c_str()); + channel.print_msg(level, line->c_str()); delete line; } } @@ -144,28 +147,28 @@ void send_line(Channel& channel, const std::string* line) { // This is the least efficient form, requiring two strings // to be allocated and freed, with an intermediate copy. // It is used only rarely. -void send_line(Channel& channel, const std::string& line) { +void send_line(Channel& channel, MsgLevel level, const std::string& line) { if (outputTask) { - send_line(channel, new std::string(line)); + send_line(channel, level, new std::string(line)); } else { - channel.println(line.c_str()); + channel.print_msg(level, line.c_str()); } } void output_loop(void* unused) { while (true) { + // Block until a message is received LogMessage message; - if (xQueueReceive(message_queue, &message, 0)) { + if (xQueueReceive(message_queue, &message, portMAX_DELAY)) { if (message.isString) { std::string* s = static_cast(message.line); - message.channel->println(s->c_str()); + message.channel->print_msg(message.level, s->c_str()); delete s; } else { const char* cp = static_cast(message.line); - message.channel->println(cp); + message.channel->print_msg(message.level, cp); } } - vTaskDelay(0); } } @@ -220,49 +223,27 @@ void start_polling() { 16000, // 8192, // size of task stack 0, // parameters - 1, // priority + 2, // priority &outputTask, // task handle SUPPORT_TASK_CORE // core ); } } -static void check_startup_state() { - // Check for and report alarm state after a reset, error, or an initial power up. - // NOTE: Sleep mode disables the stepper drivers and position can't be guaranteed. - // Re-initialize the sleep state as an ALARM mode to ensure user homes or acknowledges. - if (sys.state == State::ConfigAlarm) { - report_error_message(Message::ConfigAlarmLock); - } else { - // Perform some machine checks to make sure everything is good to go. - if (config->_start->_checkLimits && config->_axes->hasHardLimits()) { - if (limits_get_state()) { - sys.state = State::Alarm; // Ensure alarm state is active. - report_error_message(Message::CheckLimits); - } - } - if (config->_control->startup_check()) { - rtAlarm = ExecAlarm::ControlPin; - } - - if (sys.state == State::Alarm || sys.state == State::Sleep) { - report_feedback_message(Message::AlarmLock); - sys.state = State::Alarm; // Ensure alarm state is set. - } else { - // Check if the safety door is open. - sys.state = State::Idle; - while (config->_control->safety_door_ajar()) { - request_safety_door(); - protocol_execute_realtime(); // Enter safety door mode. Should return as IDLE state. - } - // All systems go! - settings_execute_startup(); // Execute startup script. - } - } +static void alarm_msg(ExecAlarm alarm_code) { + log_info_to(allChannels, "ALARM: " << alarmString(alarm_code)); + log_to(allChannels, "ALARM:", static_cast(alarm_code)); + delay_ms(500); // Force delay to ensure message clears serial write buffer. } -void protocol_main_loop() { - check_startup_state(); +static void check_startup_state() {} + +const uint32_t heapWarnThreshold = 15000; + +uint32_t heapLowWater = UINT_MAX; +uint32_t heapLowWaterReported = UINT_MAX; +int32_t heapLowWaterReportTime = 0; +void protocol_main_loop() { start_polling(); // --------------------------------------------------------------------------------- @@ -279,7 +260,10 @@ void protocol_main_loop() { Error status_code = execute_line(activeLine, *activeChannel, WebUI::AuthenticationLevel::LEVEL_GUEST); // Tell the channel that the line has been processed. - activeChannel->ack(status_code); + // If the line was aborted, the channel could be invalid + if (!sys.abort) { + activeChannel->ack(status_code); + } // Tell the input polling task that the line has been processed, // so it can give us another one when available @@ -290,8 +274,7 @@ void protocol_main_loop() { protocol_auto_cycle_start(); protocol_execute_realtime(); // Runtime command check point. if (sys.abort) { - stop_polling(); - return; // Bail to main() program loop to reset system. + sys.abort = false; } // check to see if we should disable the stepper drivers @@ -309,6 +292,25 @@ void protocol_main_loop() { idleEndTime = 0; // config->_axes->set_disable(true); } + uint32_t newHeapSize = xPortGetFreeHeapSize(); + if (newHeapSize < heapLowWater) { + heapLowWater = newHeapSize; + } + // Consider reporting when the minimum has not yet been reported and it is low enough. + if (heapLowWater < heapLowWaterReported && heapLowWater < heapWarnThreshold) { + // typecast to uint32_t handles roll-over for this case + uint32_t ticksSinceReported = (getCpuTicks() - heapLowWaterReportTime); + uint32_t tickLimit = usToCpuTicks(200000); + // Report only if it has been a while since the last report or if the memory has + // dropped significantly (2k bytes) since the last report. + // This prevents a cycle where the reporting itself consumes some heap and triggers another + // report, but the true minimum is reported eventually, and large drops are reported immediately. + if ((heapLowWater < heapLowWaterReported - 2048) || (ticksSinceReported > tickLimit)) { + log_warn("Low memory: " << heapLowWater << " bytes"); + heapLowWaterReported = heapLowWater; + heapLowWaterReportTime = getCpuTicks(); + } + } } return; /* Never reached */ } @@ -357,37 +359,95 @@ void protocol_execute_realtime() { } } -static void alarm_msg(ExecAlarm alarm_code) { - log_to(allChannels, "ALARM:", static_cast(alarm_code)); - delay_ms(500); // Force delay to ensure message clears serial write buffer. +static void protocol_run_startup_lines() { + settings_execute_startup(); // Execute startup script. } -// Executes run-time commands, when required. This function is the primary state -// machine that controls the various real-time features. -// NOTE: Do not alter this unless you know exactly what you are doing! -static void protocol_do_alarm() { - if (rtAlarm == ExecAlarm::None) { +static void protocol_do_restart() { + // Reset primary systems. + system_reset(); + protocol_reset(); + gc_init(); // Set g-code parser to default state + // Spindle should be set either by the configuration + // or by the post-configuration fixup, but we test + // it anyway just for safety. We want to avoid any + // possibility of crashing at this point. + + plan_reset(); // Clear block buffer and planner variables + + if (sys.state != State::ConfigAlarm) { + if (spindle) { + spindle->stop(); + report_ovr_counter = 0; // Set to report change immediately + } + Stepper::reset(); // Clear stepper subsystem variables + } + + // Sync cleared gcode and planner positions to current system position. + plan_sync_position(); + gc_sync_position(); + allChannels.flushRx(); + report_init_message(allChannels); + mc_init(); + + // Check for and report alarm state after a reset, error, or an initial power up. + // NOTE: Sleep mode disables the stepper drivers and position can't be guaranteed. + // Re-initialize the sleep state as an ALARM mode to ensure user homes or acknowledges. + if (sys.state == State::ConfigAlarm) { + report_error_message(Message::ConfigAlarmLock); + return; + } + + // Perform some machine checks to make sure everything is good to go. + if (config->_start->_checkLimits && config->_axes->hasHardLimits() && limits_get_state()) { + mc_critical(ExecAlarm::HardLimit); + } else if (config->_control->startup_check()) { + send_alarm(ExecAlarm::ControlPin); + } else { + if (sys.state == State::Idle) { + config->_macros->_after_reset.run(); + } + } +} + +static void protocol_do_start() { + protocol_send_event(&restartEvent); + sys.state = State::Critical; + if (FORCE_INITIALIZATION_ALARM) { + // Force ALARM state upon a power-cycle or hard reset. + send_alarm(ExecAlarm::Init); return; } + Homing::set_all_axes_homed(); + if (config->_start->_mustHome && Machine::Axes::homingMask) { + Homing::set_all_axes_unhomed(); + // If there is an axis with homing configured, enter Alarm state on startup + send_alarm(ExecAlarm::Unhomed); + } else { + sys.state = State::Idle; + } + protocol_send_event(&runStartupLinesEvent); +} + +static void protocol_do_alarm(void* alarmVoid) { + lastAlarm = (ExecAlarm)((int)alarmVoid); if (spindle->_off_on_alarm) { spindle->stop(); } - sys.state = State::Alarm; // Set system alarm state - alarm_msg(rtAlarm); - if (rtAlarm == ExecAlarm::HardLimit || rtAlarm == ExecAlarm::SoftLimit) { + alarm_msg(lastAlarm); + if (lastAlarm == ExecAlarm::HardLimit || lastAlarm == ExecAlarm::HardStop) { + sys.state = State::Critical; // Set system alarm state report_error_message(Message::CriticalEvent); protocol_disable_steppers(); - rtReset = false; // Disable any existing reset - do { - protocol_handle_events(); - // Block everything except reset and status reports until user issues reset or power - // cycles. Hard limits typically occur while unattended or not paying attention. Gives - // the user and a GUI time to do what is needed before resetting, like killing the - // incoming stream. The same could be said about soft limits. While the position is not - // lost, continued streaming could cause a serious crash if by chance it gets executed. - } while (!rtReset); + Homing::set_all_axes_unhomed(); + return; + } + if (lastAlarm == ExecAlarm::SoftLimit) { + sys.state = State::Critical; // Set system alarm state + report_error_message(Message::CriticalEvent); + return; } - rtAlarm = ExecAlarm::None; + sys.state = State::Alarm; } static void protocol_start_holding() { @@ -590,8 +650,7 @@ static void protocol_do_initiate_cycle() { sys.state = pb->is_jog ? State::Jog : State::Cycle; Stepper::prep_buffer(); // Initialize step segment buffer before beginning cycle. Stepper::wake_up(); - } else { // Otherwise, do nothing. Set and resume IDLE state. - + } else { // Otherwise, do nothing. Set and resume IDLE state. sys.suspend.value = 0; // Break suspend state. sys.state = State::Idle; } @@ -653,7 +712,7 @@ void protocol_disable_steppers() { config->_axes->set_disable(false); return; } - if (sys.state == State::Sleep || rtAlarm != ExecAlarm::None) { + if (sys.state == State::Sleep || sys.state == State::Alarm) { // Disable steppers immediately in sleep or alarm state config->_axes->set_disable(true); return; @@ -702,6 +761,7 @@ void protocol_do_cycle_stop() { // Fall through case State::ConfigAlarm: case State::Alarm: + break; case State::CheckMode: case State::Idle: case State::Cycle: @@ -736,7 +796,7 @@ static void update_velocities() { plan_cycle_reinitialize(); } -// This is the final phase of the shutdown activity that is initiated by mc_reset(). +// This is the final phase of the shutdown activity for a reset // The stuff herein is not necessarily safe to do in an ISR. static void protocol_do_late_reset() { // Kill spindle and coolant. @@ -752,22 +812,10 @@ static void protocol_do_late_reset() { // do we need to stop a running file job? allChannels.stopJob(); + sys.abort = true; } void protocol_exec_rt_system() { - protocol_do_alarm(); // If there is a hard or soft limit, this will block until rtReset is set - - if (rtReset) { - rtReset = false; - if (sys.state == State::Homing) { - Machine::Homing::fail(ExecAlarm::HomingFailReset); - } - protocol_do_late_reset(); - // Trigger system abort. - sys.abort = true; // Only place this is set true. - return; // Nothing else to do but exit. - } - if (rtSafetyDoor) { protocol_do_safety_door(); } @@ -1002,21 +1050,43 @@ static void protocol_do_limit(void* arg) { Machine::Homing::limitReached(); return; } + if ((sys.state == State::Cycle || sys.state == State::Jog) && limit->isHard()) { + mc_critical(ExecAlarm::HardLimit); + } log_debug("Limit switch tripped for " << config->_axes->axisName(limit->_axis) << " motor " << limit->_motorNum); +} +static void protocol_do_fault_pin(void* arg) { if (sys.state == State::Cycle || sys.state == State::Jog) { - if (limit->isHard() && rtAlarm == ExecAlarm::None) { - log_debug("Hard limits"); - mc_reset(); // Initiate system kill. - rtAlarm = ExecAlarm::HardLimit; // Indicate hard limit critical event + mc_critical(ExecAlarm::HardStop); // Initiate system kill. + } + ControlPin* pin = (ControlPin*)arg; + log_info("Stopped by " << pin->_legend); +} +void protocol_do_rt_reset() { + if (sys.state == State::Homing) { + Machine::Homing::fail(ExecAlarm::HomingFailReset); + } else if (sys.state == State::Cycle || sys.state == State::Jog || sys.step_control.executeHold || sys.step_control.executeSysMotion) { + Stepper::stop_stepping(); // Stop stepping immediately, possibly losing position + protocol_do_alarm((void*)ExecAlarm::AbortCycle); + } else if (sys.state == State::Critical) { + if (Homing::unhomed_axes()) { + protocol_do_alarm((void*)ExecAlarm::Unhomed); + } else { + sys.state = State::Idle; } - return; + } else if (sys.state != State::Alarm) { + sys.state = State::Idle; } + protocol_do_late_reset(); + protocol_send_event(&restartEvent); } + ArgEvent feedOverrideEvent { protocol_do_feed_override }; ArgEvent rapidOverrideEvent { protocol_do_rapid_override }; ArgEvent spindleOverrideEvent { protocol_do_spindle_override }; ArgEvent accessoryOverrideEvent { protocol_do_accessory_override }; ArgEvent limitEvent { protocol_do_limit }; +ArgEvent faultPinEvent { protocol_do_fault_pin }; ArgEvent reportStatusEvent { (void (*)(void*))report_realtime_status }; @@ -1027,12 +1097,15 @@ NoArgEvent cycleStopEvent { protocol_do_cycle_stop }; NoArgEvent motionCancelEvent { protocol_do_motion_cancel }; NoArgEvent sleepEvent { protocol_do_sleep }; NoArgEvent debugEvent { report_realtime_debug }; +NoArgEvent startEvent { protocol_do_start }; +NoArgEvent restartEvent { protocol_do_restart }; +NoArgEvent runStartupLinesEvent { protocol_run_startup_lines }; -// Only mc_reset() is permitted to set rtReset. -NoArgEvent resetEvent { mc_reset }; +NoArgEvent rtResetEvent { protocol_do_rt_reset }; // The problem is that report_realtime_status needs a channel argument // Event statusReportEvent { protocol_do_status_report(XXX) }; +ArgEvent alarmEvent { (void (*)(void*))protocol_do_alarm }; xQueueHandle event_queue; @@ -1052,7 +1125,12 @@ void protocol_send_event(Event* evt, void* arg) { void protocol_handle_events() { EventItem item; while (xQueueReceive(event_queue, &item, 0)) { - // log_debug("event"); item.event->run(item.arg); } } +void send_alarm(ExecAlarm alarm) { + protocol_send_event(&alarmEvent, (void*)alarm); +} +void IRAM_ATTR send_alarm_from_ISR(ExecAlarm alarm) { + protocol_send_event_from_ISR(&alarmEvent, (void*)alarm); +} diff --git a/FluidNC/src/Protocol.h b/FluidNC/src/Protocol.h index 8234d2864..2d3e50e12 100644 --- a/FluidNC/src/Protocol.h +++ b/FluidNC/src/Protocol.h @@ -44,7 +44,6 @@ void protocol_buffer_synchronize(); void protocol_disable_steppers(); void protocol_cancel_disable_steppers(); -extern volatile bool rtReset; extern volatile bool rtCycleStop; extern volatile bool runLimitLoop; @@ -64,13 +63,18 @@ enum class ExecAlarm : uint8_t { SpindleControl = 10, ControlPin = 11, HomingAmbiguousSwitch = 12, + HardStop = 13, + Unhomed = 14, + Init = 15, }; -extern volatile ExecAlarm rtAlarm; // Global realtime executor variable for setting various alarms. +extern volatile ExecAlarm lastAlarm; #include extern std::map AlarmNames; +const char* alarmString(ExecAlarm alarmNumber); + #include "Event.h" enum AccessoryOverride { SpindleStopOvr = 1, @@ -83,6 +87,7 @@ extern ArgEvent rapidOverrideEvent; extern ArgEvent spindleOverrideEvent; extern ArgEvent accessoryOverrideEvent; extern ArgEvent limitEvent; +extern ArgEvent faultPinEvent; extern ArgEvent reportStatusEvent; @@ -92,8 +97,13 @@ extern NoArgEvent cycleStartEvent; extern NoArgEvent cycleStopEvent; extern NoArgEvent motionCancelEvent; extern NoArgEvent sleepEvent; -extern NoArgEvent resetEvent; +extern NoArgEvent rtResetEvent; extern NoArgEvent debugEvent; +extern NoArgEvent unhomedEvent; +extern NoArgEvent startEvent; +extern NoArgEvent restartEvent; + +extern NoArgEvent runStartupLinesEvent; // extern NoArgEvent statusReportEvent; @@ -109,14 +119,19 @@ struct EventItem { void protocol_send_event(Event*, void* arg = 0); void protocol_handle_events(); +void send_alarm(ExecAlarm alarm); +void send_alarm_from_ISR(ExecAlarm alarm); + inline void protocol_send_event(Event* evt, int arg) { protocol_send_event(evt, (void*)arg); } void protocol_send_event_from_ISR(Event* evt, void* arg = 0); -void send_line(Channel& channel, const char* message); -void send_line(Channel& channel, const std::string* message); -void send_line(Channel& channel, const std::string& message); +void send_line(Channel& channel, MsgLevel level, const char* message); +void send_line(Channel& channel, MsgLevel level, const std::string* message); +void send_line(Channel& channel, MsgLevel level, const std::string& message); void drain_messages(); + +extern uint32_t heapLowWater; diff --git a/FluidNC/src/RealtimeCmd.cpp b/FluidNC/src/RealtimeCmd.cpp new file mode 100644 index 000000000..aeb696cd2 --- /dev/null +++ b/FluidNC/src/RealtimeCmd.cpp @@ -0,0 +1,110 @@ +#include "RealtimeCmd.h" +#include "Config.h" +#include "Channel.h" +#include "Protocol.h" +#include "Report.h" +#include "System.h" +#include "Machine/Macros.h" // macroNEvent + +// Act upon a realtime character +void execute_realtime_command(Cmd command, Channel& channel) { + switch (command) { + case Cmd::Reset: + log_debug("Cmd::Reset"); + protocol_send_event(&rtResetEvent); + break; + case Cmd::StatusReport: + report_realtime_status(channel); // direct call instead of setting flag + // protocol_send_event(&reportStatusEvent, int(&channel)); + break; + case Cmd::CycleStart: + protocol_send_event(&cycleStartEvent); + break; + case Cmd::FeedHold: + protocol_send_event(&feedHoldEvent); + break; + case Cmd::SafetyDoor: + protocol_send_event(&safetyDoorEvent); + break; + case Cmd::JogCancel: + if (sys.state == State::Jog) { // Block all other states from invoking motion cancel. + protocol_send_event(&motionCancelEvent); + } + break; + case Cmd::DebugReport: + protocol_send_event(&debugEvent); + break; + case Cmd::SpindleOvrStop: + protocol_send_event(&accessoryOverrideEvent, AccessoryOverride::SpindleStopOvr); + break; + case Cmd::FeedOvrReset: + protocol_send_event(&feedOverrideEvent, FeedOverride::Default); + break; + case Cmd::FeedOvrCoarsePlus: + protocol_send_event(&feedOverrideEvent, FeedOverride::CoarseIncrement); + break; + case Cmd::FeedOvrCoarseMinus: + protocol_send_event(&feedOverrideEvent, -FeedOverride::CoarseIncrement); + break; + case Cmd::FeedOvrFinePlus: + protocol_send_event(&feedOverrideEvent, FeedOverride::FineIncrement); + break; + case Cmd::FeedOvrFineMinus: + protocol_send_event(&feedOverrideEvent, -FeedOverride::FineIncrement); + break; + case Cmd::RapidOvrReset: + protocol_send_event(&rapidOverrideEvent, RapidOverride::Default); + break; + case Cmd::RapidOvrMedium: + protocol_send_event(&rapidOverrideEvent, RapidOverride::Medium); + break; + case Cmd::RapidOvrLow: + protocol_send_event(&rapidOverrideEvent, RapidOverride::Low); + break; + case Cmd::RapidOvrExtraLow: + protocol_send_event(&rapidOverrideEvent, RapidOverride::ExtraLow); + break; + case Cmd::SpindleOvrReset: + protocol_send_event(&spindleOverrideEvent, SpindleSpeedOverride::Default); + break; + case Cmd::SpindleOvrCoarsePlus: + protocol_send_event(&spindleOverrideEvent, SpindleSpeedOverride::CoarseIncrement); + break; + case Cmd::SpindleOvrCoarseMinus: + protocol_send_event(&spindleOverrideEvent, -SpindleSpeedOverride::CoarseIncrement); + break; + case Cmd::SpindleOvrFinePlus: + protocol_send_event(&spindleOverrideEvent, SpindleSpeedOverride::FineIncrement); + break; + case Cmd::SpindleOvrFineMinus: + protocol_send_event(&spindleOverrideEvent, -SpindleSpeedOverride::FineIncrement); + break; + case Cmd::CoolantFloodOvrToggle: + protocol_send_event(&accessoryOverrideEvent, AccessoryOverride::FloodToggle); + break; + case Cmd::CoolantMistOvrToggle: + protocol_send_event(&accessoryOverrideEvent, AccessoryOverride::MistToggle); + break; + case Cmd::Macro0: + protocol_send_event(¯o0Event); + break; + case Cmd::Macro1: + protocol_send_event(¯o1Event); + break; + case Cmd::Macro2: + protocol_send_event(¯o2Event); + break; + case Cmd::Macro3: + protocol_send_event(¯o3Event); + break; + } +} + +// checks to see if a character is a realtime character +bool is_realtime_command(uint8_t data) { + if (data >= 0x80) { + return true; + } + auto cmd = static_cast(data); + return cmd == Cmd::Reset || cmd == Cmd::StatusReport || cmd == Cmd::CycleStart || cmd == Cmd::FeedHold; +} diff --git a/FluidNC/src/RealtimeCmd.h b/FluidNC/src/RealtimeCmd.h new file mode 100644 index 000000000..bb9fea62e --- /dev/null +++ b/FluidNC/src/RealtimeCmd.h @@ -0,0 +1,53 @@ +#pragma once + +#include + +// Define realtime command special characters. These characters are 'picked-off' directly from the +// serial read data stream and are not passed to the grbl line execution parser. Select characters +// that do not and must not exist in the streamed GCode program. ASCII control characters may be +// used, if they are available per user setup. Also, extended ASCII codes (>127), which are never in +// GCode programs, maybe selected for interface programs. +// NOTE: If changed, manually update help message in report.c. + +// NOTE: All override realtime commands must be in the extended ASCII character set, starting +// at character value 128 (0x80) and up to 255 (0xFF). If the normal set of realtime commands, +// such as status reports, feed hold, reset, and cycle start, are moved to the extended set +// space, serial.c's RX ISR will need to be modified to accommodate the change. + +enum class Cmd : uint8_t { + None = 0, + Reset = 0x18, // Ctrl-X + StatusReport = '?', + CycleStart = '~', + FeedHold = '!', + SafetyDoor = 0x84, + JogCancel = 0x85, + DebugReport = 0x86, // Only when DEBUG_REPORT_REALTIME enabled, sends debug report in '{}' braces. + Macro0 = 0x87, + Macro1 = 0x88, + Macro2 = 0x89, + Macro3 = 0x8a, + FeedOvrReset = 0x90, // Restores feed override value to 100%. + FeedOvrCoarsePlus = 0x91, + FeedOvrCoarseMinus = 0x92, + FeedOvrFinePlus = 0x93, + FeedOvrFineMinus = 0x94, + RapidOvrReset = 0x95, // Restores rapid override value to 100%. + RapidOvrMedium = 0x96, + RapidOvrLow = 0x97, + RapidOvrExtraLow = 0x98, // *NOT SUPPORTED* + SpindleOvrReset = 0x99, // Restores spindle override value to 100%. + SpindleOvrCoarsePlus = 0x9A, // 154 + SpindleOvrCoarseMinus = 0x9B, + SpindleOvrFinePlus = 0x9C, + SpindleOvrFineMinus = 0x9D, + SpindleOvrStop = 0x9E, + CoolantFloodOvrToggle = 0xA0, + CoolantMistOvrToggle = 0xA1, + // Channel Extender uses the Bx range; see Channel.h +}; + +class Channel; + +bool is_realtime_command(uint8_t data); +void execute_realtime_command(Cmd command, Channel& channel); diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index dc43c3dec..ee31f1e03 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -45,6 +45,10 @@ EspClass esp; #endif +volatile bool protocol_pin_changed = false; + +std::string report_pin_string; + portMUX_TYPE mmux = portMUX_INITIALIZER_UNLOCKED; void _notify(const char* title, const char* msg) { @@ -121,6 +125,7 @@ std::map MessageText = { { Message::RestoreDefaults, "Restoring defaults" }, { Message::SpindleRestore, "Restoring spindle" }, { Message::SleepMode, "Sleeping" }, + { Message::HardStop, "Hard stop" }, { Message::ConfigAlarmLock, "Configuration is invalid. Check boot messages for ERR's." }, // Handled separately due to numeric argument // { Message::FileQuit, "Reset during file job at line: %d" }, @@ -469,6 +474,7 @@ const char* state_name() { return "Jog"; case State::Homing: return "Home"; + case State::Critical: case State::ConfigAlarm: case State::Alarm: return "Alarm"; @@ -489,15 +495,10 @@ const char* state_name() { return ""; } -static std::string pinString() { - std::string msg; - bool prefixNeeded = true; +void report_recompute_pin_string() { + report_pin_string = ""; if (config->_probe->get_state()) { - if (prefixNeeded) { - prefixNeeded = false; - msg += "|Pn:"; - } - msg += 'P'; + report_pin_string += 'P'; } MotorMask lim_pin_state = limits_get_state(); @@ -506,24 +507,15 @@ static std::string pinString() { for (size_t axis = 0; axis < n_axis; axis++) { if (bitnum_is_true(lim_pin_state, Machine::Axes::motor_bit(axis, 0)) || bitnum_is_true(lim_pin_state, Machine::Axes::motor_bit(axis, 1))) { - if (prefixNeeded) { - prefixNeeded = false; - msg += "|Pn:"; - } - msg += config->_axes->axisName(axis); + report_pin_string += config->_axes->axisName(axis); } } } std::string ctrl_pin_report = config->_control->report_status(); if (ctrl_pin_report.length()) { - if (prefixNeeded) { - prefixNeeded = false; - msg += "|Pn:"; - } - msg += ctrl_pin_report; + report_pin_string += ctrl_pin_report; } - return msg; } // Define this to do something if a debug request comes in over serial @@ -572,7 +564,9 @@ void report_realtime_status(Channel& channel) { } msg << "|FS:" << setprecision(0) << rate << "," << sys.spindle_speed; - msg << pinString(); + if (report_pin_string.length()) { + msg << "|Pn:" << report_pin_string; + } if (report_wco_counter > 0) { report_wco_counter--; @@ -643,11 +637,10 @@ void report_realtime_status(Channel& channel) { msg << "|ISRs:" << Stepper::isr_count; #endif #ifdef DEBUG_REPORT_HEAP - msg << "|Heap:" << esp.getHeapSize(); + msg << "|Heap:" << xPortGetFreeHeapSize(); #endif msg << ">"; - // The DebugStream destructor sends the line - // when msg goes out of scope + // The destructor sends the line when msg goes out of scope } void hex_msg(uint8_t* buf, const char* prefix, int len) { diff --git a/FluidNC/src/Report.h b/FluidNC/src/Report.h index 1c1885a80..d90ab815e 100644 --- a/FluidNC/src/Report.h +++ b/FluidNC/src/Report.h @@ -37,7 +37,8 @@ enum class Message : uint8_t { SpindleRestore = 10, SleepMode = 11, ConfigAlarmLock = 12, - FileQuit = 60, // mc_reset was called during a file job + HardStop = 13, + FileQuit = 60, // mc_critical was called during a file job }; typedef uint8_t Counter; // Report interval @@ -91,8 +92,12 @@ const char* state_name(); extern const char* grbl_version; extern const char* git_info; +extern const char* git_url; // Callout to custom code void display_init(); extern bool readyNext; + +extern std::string report_pin_string; +void report_recompute_pin_string(); diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index 58c1eb353..05715d5aa 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -60,7 +60,8 @@ #include #include // portMUX_TYPE, TaskHandle_T -std::mutex AllChannels::_mutex; +std::mutex AllChannels::_mutex_general; +std::mutex AllChannels::_mutex_pollLine; static TaskHandle_t channelCheckTaskHandle = 0; @@ -82,188 +83,114 @@ void heapCheckTask(void* pvParameters) { } } -// Act upon a realtime character -void execute_realtime_command(Cmd command, Channel& channel) { - switch (command) { - case Cmd::Reset: - log_debug("Cmd::Reset"); - protocol_send_event(&resetEvent); - break; - case Cmd::StatusReport: - report_realtime_status(channel); // direct call instead of setting flag - // protocol_send_event(&reportStatusEvent, int(&channel)); - break; - case Cmd::CycleStart: - protocol_send_event(&cycleStartEvent); - break; - case Cmd::FeedHold: - protocol_send_event(&feedHoldEvent); - break; - case Cmd::SafetyDoor: - protocol_send_event(&safetyDoorEvent); - break; - case Cmd::JogCancel: - if (sys.state == State::Jog) { // Block all other states from invoking motion cancel. - protocol_send_event(&motionCancelEvent); - } - break; - case Cmd::DebugReport: - protocol_send_event(&debugEvent); - break; - case Cmd::SpindleOvrStop: - protocol_send_event(&accessoryOverrideEvent, AccessoryOverride::SpindleStopOvr); - break; - case Cmd::FeedOvrReset: - protocol_send_event(&feedOverrideEvent, FeedOverride::Default); - break; - case Cmd::FeedOvrCoarsePlus: - protocol_send_event(&feedOverrideEvent, FeedOverride::CoarseIncrement); - break; - case Cmd::FeedOvrCoarseMinus: - protocol_send_event(&feedOverrideEvent, -FeedOverride::CoarseIncrement); - break; - case Cmd::FeedOvrFinePlus: - protocol_send_event(&feedOverrideEvent, FeedOverride::FineIncrement); - break; - case Cmd::FeedOvrFineMinus: - protocol_send_event(&feedOverrideEvent, -FeedOverride::FineIncrement); - break; - case Cmd::RapidOvrReset: - protocol_send_event(&rapidOverrideEvent, RapidOverride::Default); - break; - case Cmd::RapidOvrMedium: - protocol_send_event(&rapidOverrideEvent, RapidOverride::Medium); - break; - case Cmd::RapidOvrLow: - protocol_send_event(&rapidOverrideEvent, RapidOverride::Low); - break; - case Cmd::RapidOvrExtraLow: - protocol_send_event(&rapidOverrideEvent, RapidOverride::ExtraLow); - break; - case Cmd::SpindleOvrReset: - protocol_send_event(&spindleOverrideEvent, SpindleSpeedOverride::Default); - break; - case Cmd::SpindleOvrCoarsePlus: - protocol_send_event(&spindleOverrideEvent, SpindleSpeedOverride::CoarseIncrement); - break; - case Cmd::SpindleOvrCoarseMinus: - protocol_send_event(&spindleOverrideEvent, -SpindleSpeedOverride::CoarseIncrement); - break; - case Cmd::SpindleOvrFinePlus: - protocol_send_event(&spindleOverrideEvent, SpindleSpeedOverride::FineIncrement); - break; - case Cmd::SpindleOvrFineMinus: - protocol_send_event(&spindleOverrideEvent, -SpindleSpeedOverride::FineIncrement); - break; - case Cmd::CoolantFloodOvrToggle: - protocol_send_event(&accessoryOverrideEvent, AccessoryOverride::FloodToggle); - break; - case Cmd::CoolantMistOvrToggle: - protocol_send_event(&accessoryOverrideEvent, AccessoryOverride::MistToggle); - break; - case Cmd::Macro0: - protocol_send_event(¯o0Event); - break; - case Cmd::Macro1: - protocol_send_event(¯o1Event); - break; - case Cmd::Macro2: - protocol_send_event(¯o2Event); - break; - case Cmd::Macro3: - protocol_send_event(¯o3Event); - break; - } -} - -// checks to see if a character is a realtime character -bool is_realtime_command(uint8_t data) { - if (data >= 0x80) { - return true; - } - auto cmd = static_cast(data); - return cmd == Cmd::Reset || cmd == Cmd::StatusReport || cmd == Cmd::CycleStart || cmd == Cmd::FeedHold; -} - void AllChannels::init() { registration(&WebUI::inputBuffer); // Macros registration(&startupLog); // Early startup messages for $SS } +void AllChannels::ready() { + for (auto channel : _channelq) { + channel->ready(); + } +} + void AllChannels::kill(Channel* channel) { xQueueSend(_killQueue, &channel, 0); } void AllChannels::registration(Channel* channel) { - _mutex.lock(); + _mutex_general.lock(); + _mutex_pollLine.lock(); _channelq.push_back(channel); - _mutex.unlock(); + _mutex_pollLine.unlock(); + _mutex_general.unlock(); } void AllChannels::deregistration(Channel* channel) { - _mutex.lock(); + _mutex_general.lock(); + _mutex_pollLine.lock(); if (channel == _lastChannel) { _lastChannel = nullptr; } _channelq.erase(std::remove(_channelq.begin(), _channelq.end(), channel), _channelq.end()); - _mutex.unlock(); + _mutex_pollLine.unlock(); + _mutex_general.unlock(); } void AllChannels::listChannels(Channel& out) { - _mutex.lock(); + _mutex_general.lock(); std::string retval; for (auto channel : _channelq) { log_to(out, channel->name()); } - _mutex.unlock(); + _mutex_general.unlock(); } void AllChannels::flushRx() { - _mutex.lock(); + _mutex_general.lock(); for (auto channel : _channelq) { channel->flushRx(); } - _mutex.unlock(); + _mutex_general.unlock(); } size_t AllChannels::write(uint8_t data) { - _mutex.lock(); + _mutex_general.lock(); for (auto channel : _channelq) { channel->write(data); } - _mutex.unlock(); + _mutex_general.unlock(); return 1; } void AllChannels::notifyWco(void) { - _mutex.lock(); + _mutex_general.lock(); for (auto channel : _channelq) { channel->notifyWco(); } - _mutex.unlock(); + _mutex_general.unlock(); } void AllChannels::notifyNgc(CoordIndex coord) { - _mutex.lock(); + _mutex_general.lock(); for (auto channel : _channelq) { channel->notifyNgc(coord); } - _mutex.unlock(); + _mutex_general.unlock(); } void AllChannels::stopJob() { - _mutex.lock(); + _mutex_general.lock(); for (auto channel : _channelq) { channel->stopJob(); } - _mutex.unlock(); + _mutex_general.unlock(); } size_t AllChannels::write(const uint8_t* buffer, size_t length) { - _mutex.lock(); + _mutex_general.lock(); for (auto channel : _channelq) { channel->write(buffer, length); } - _mutex.unlock(); + _mutex_general.unlock(); return length; } +void AllChannels::print_msg(MsgLevel level, const char* msg) { + _mutex_general.lock(); + for (auto channel : _channelq) { + channel->print_msg(level, msg); + } + _mutex_general.unlock(); +} + +Channel* AllChannels::find(const std::string& name) { + _mutex_general.lock(); + for (auto channel : _channelq) { + if (channel->name() == name) { + _mutex_general.unlock(); + return channel; + } + } + _mutex_general.unlock(); + return nullptr; +} Channel* AllChannels::pollLine(char* line) { Channel* deadChannel; while (xQueueReceive(_killQueue, &deadChannel, 0)) { @@ -274,17 +201,17 @@ Channel* AllChannels::pollLine(char* line) { // To avoid starving other channels when one has a lot // of traffic, we poll the other channels before the last // one that returned a line. - _mutex.lock(); + _mutex_pollLine.lock(); for (auto channel : _channelq) { // Skip the last channel in the loop - if (channel != _lastChannel && channel->pollLine(line)) { + if (channel != _lastChannel && channel && channel->pollLine(line)) { _lastChannel = channel; - _mutex.unlock(); + _mutex_pollLine.unlock(); return _lastChannel; } } - _mutex.unlock(); + _mutex_pollLine.unlock(); // If no other channel returned a line, try the last one if (_lastChannel && _lastChannel->pollLine(line)) { return _lastChannel; diff --git a/FluidNC/src/Serial.h b/FluidNC/src/Serial.h index b558953f4..1896fbec0 100644 --- a/FluidNC/src/Serial.h +++ b/FluidNC/src/Serial.h @@ -21,53 +21,6 @@ uint8_t check_action_command(uint8_t data); void channel_init(); -// Define realtime command special characters. These characters are 'picked-off' directly from the -// serial read data stream and are not passed to the grbl line execution parser. Select characters -// that do not and must not exist in the streamed GCode program. ASCII control characters may be -// used, if they are available per user setup. Also, extended ASCII codes (>127), which are never in -// GCode programs, maybe selected for interface programs. -// NOTE: If changed, manually update help message in report.c. - -// NOTE: All override realtime commands must be in the extended ASCII character set, starting -// at character value 128 (0x80) and up to 255 (0xFF). If the normal set of realtime commands, -// such as status reports, feed hold, reset, and cycle start, are moved to the extended set -// space, serial.c's RX ISR will need to be modified to accommodate the change. - -enum class Cmd : uint8_t { - None = 0, - Reset = 0x18, // Ctrl-X - StatusReport = '?', - CycleStart = '~', - FeedHold = '!', - SafetyDoor = 0x84, - JogCancel = 0x85, - DebugReport = 0x86, // Only when DEBUG_REPORT_REALTIME enabled, sends debug report in '{}' braces. - Macro0 = 0x87, - Macro1 = 0x88, - Macro2 = 0x89, - Macro3 = 0x8a, - FeedOvrReset = 0x90, // Restores feed override value to 100%. - FeedOvrCoarsePlus = 0x91, - FeedOvrCoarseMinus = 0x92, - FeedOvrFinePlus = 0x93, - FeedOvrFineMinus = 0x94, - RapidOvrReset = 0x95, // Restores rapid override value to 100%. - RapidOvrMedium = 0x96, - RapidOvrLow = 0x97, - RapidOvrExtraLow = 0x98, // *NOT SUPPORTED* - SpindleOvrReset = 0x99, // Restores spindle override value to 100%. - SpindleOvrCoarsePlus = 0x9A, // 154 - SpindleOvrCoarseMinus = 0x9B, - SpindleOvrFinePlus = 0x9C, - SpindleOvrFineMinus = 0x9D, - SpindleOvrStop = 0x9E, - CoolantFloodOvrToggle = 0xA0, - CoolantMistOvrToggle = 0xA1, -}; - -bool is_realtime_command(uint8_t data); -void execute_realtime_command(Cmd command, Channel& channel); - Channel* pollChannels(char* line = nullptr); class AllChannels : public Channel { @@ -76,7 +29,8 @@ class AllChannels : public Channel { Channel* _lastChannel = nullptr; xQueueHandle _killQueue; - static std::mutex _mutex; + static std::mutex _mutex_general; + static std::mutex _mutex_pollLine; public: AllChannels() : Channel("all") { _killQueue = xQueueCreate(3, sizeof(Channel*)); } @@ -86,10 +40,13 @@ class AllChannels : public Channel { void registration(Channel* channel); void deregistration(Channel* channel); void init(); + void ready(); size_t write(uint8_t data) override; size_t write(const uint8_t* buffer, size_t length) override; + void print_msg(MsgLevel level, const char* msg) override; + void flushRx(); void notifyWco(); @@ -98,6 +55,7 @@ class AllChannels : public Channel { void listChannels(Channel& out); Channel* pollLine(char* line) override; + Channel* find(const std::string& name); void stopJob() override; }; diff --git a/FluidNC/src/Settings.cpp b/FluidNC/src/Settings.cpp index ded02e2a3..9a38065f6 100644 --- a/FluidNC/src/Settings.cpp +++ b/FluidNC/src/Settings.cpp @@ -5,6 +5,7 @@ #include "WebUI/Commands.h" // WebUI::COMMANDS #include "System.h" // sys #include "Protocol.h" // protocol_buffer_synchronize +#include "Machine/MachineConfig.h" #include #include @@ -12,6 +13,9 @@ #include #include +std::vector Setting::List __attribute__((init_priority(101))) = {}; +std::vector Command::List __attribute__((init_priority(102))) = {}; + bool anyState() { return false; } @@ -28,24 +32,18 @@ bool cycleOrHold() { Word::Word(type_t type, permissions_t permissions, const char* description, const char* grblName, const char* fullName) : _description(description), _grblName(grblName), _fullName(fullName), _type(type), _permissions(permissions) {} -Command* Command::List = NULL; - Command::Command( const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*cmdChecker)()) : Word(type, permissions, description, grblName, fullName), _cmdChecker(cmdChecker) { - link = List; - List = this; + List.insert(List.begin(), this); } -Setting* Setting::List = NULL; - Setting::Setting( const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*checker)(char*)) : Word(type, permissions, description, grblName, fullName), _checker(checker) { - link = List; - List = this; + List.insert(List.begin(), this); // NVS keys are limited to 15 characters, so if the setting name is longer // than that, we derive a 15-character name from a hash function @@ -265,10 +263,10 @@ static bool isPassword(bool (*_checker)(char*)) { const char* StringSetting::getDefaultString() { // If the string is a password do not display it - return (_checker && isPassword(_checker)) ? "******" : _defaultValue.c_str(); + return (_checker && isPassword(_checker)) ? "********" : _defaultValue.c_str(); } const char* StringSetting::getStringValue() { - return (_checker && isPassword(_checker)) ? "******" : get(); + return (_checker && isPassword(_checker)) ? "********" : get(); } void StringSetting::addWebui(WebUI::JSONencoder* j) { @@ -521,3 +519,18 @@ void IPaddrSetting::addWebui(WebUI::JSONencoder* j) { j->end_object(); } } + +template <> +const char* MachineConfigProxySetting::getStringValue() { + auto got = _getter(*MachineConfig::instance()); + _cachedValue.reserve(16); + std::snprintf(_cachedValue.data(), _cachedValue.capacity(), "%.3f", got); + return _cachedValue.c_str(); +} + +template <> +const char* MachineConfigProxySetting::getStringValue() { + auto got = _getter(*MachineConfig::instance()); + _cachedValue = std::to_string(got); + return _cachedValue.c_str(); +} diff --git a/FluidNC/src/Settings.h b/FluidNC/src/Settings.h index 19577f3cb..303ae0159 100644 --- a/FluidNC/src/Settings.h +++ b/FluidNC/src/Settings.h @@ -5,9 +5,15 @@ #include "Report.h" // info_channel #include "GCode.h" // CoordIndex +#include #include #include +// forward declarations +namespace Machine { + class MachineConfig; +} + // Initialize the configuration subsystem void settings_init(); @@ -24,11 +30,6 @@ enum SettingsRestore { // Restore subsets of settings to default values void settings_restore(uint8_t restore_flag); -// Command::List is a linked list of all settings, -// so common code can enumerate them. -class Command; -// extern Command *CommandsList; - // This abstract class defines the generic interface that // is used to set and get values for all settings independent // of their underlying data type. The values are always @@ -78,12 +79,12 @@ class Word { class Command : public Word { protected: - Command* link; // linked list of setting objects bool (*_cmdChecker)(); public: - static Command* List; - Command* next() { return link; } + // Command::List is a vector of all commands, + // so common code can enumerate them. + static std::vector List; ~Command() {} Command(const char* description, type_t type, permissions_t permissions, const char* grblName, const char* fullName, bool (*cmdChecker)()); @@ -99,8 +100,7 @@ class Setting : public Word { private: protected: // group_t _group; - axis_t _axis = NO_AXIS; - Setting* link; // linked list of setting objects + axis_t _axis = NO_AXIS; bool (*_checker)(char*); const char* _keyName; @@ -108,8 +108,10 @@ class Setting : public Word { public: static nvs_handle _handle; static void init(); - static Setting* List; - Setting* next() { return link; } + + // Setting::List is a vector of all settings, + // so common code can enumerate them. + static std::vector List; Error check(char* s); @@ -201,6 +203,21 @@ class IntSetting : public Setting { int32_t get() { return _currentValue; } }; +// See Settings.cpp for the int32_t and float specialization implementations +template +class MachineConfigProxySetting : public Setting { + std::function _getter; + std::string _cachedValue; + +public: + MachineConfigProxySetting(const char* grblName, const char* fullName, std::function getter) : + Setting(fullName, type_t::GRBL, permissions_t::WU, grblName, fullName, nullptr), _getter(getter), _cachedValue("") {} + + const char* getStringValue() override; + Error setStringValue(char* value) override { return Error::ReadOnlySetting; } + const char* getDefaultString() override { return ""; } +}; + class Coordinates { private: float _currentValue[MAX_N_AXIS]; diff --git a/FluidNC/src/SettingsDefinitions.cpp b/FluidNC/src/SettingsDefinitions.cpp index e0ccc7c98..f67f823af 100644 --- a/FluidNC/src/SettingsDefinitions.cpp +++ b/FluidNC/src/SettingsDefinitions.cpp @@ -1,6 +1,11 @@ +#include "Machine/MachineConfig.h" #include "SettingsDefinitions.h" #include "Config.h" +#include +#include +#include + StringSetting* config_filename; StringSetting* build_info; @@ -13,6 +18,9 @@ IntSetting* sd_fallback_cs; EnumSetting* message_level; +std::vector>> float_proxies; +std::vector>> int_proxies; + enum_opt_t messageLevels = { // clang-format off { "None", MsgLevelNone }, @@ -35,6 +43,14 @@ void make_coordinate(CoordIndex index, const char* name) { } } +#define FLOAT_PROXY(number, name, configvar) \ + float_proxies.emplace_back( \ + std::make_unique>(number, name, [](MachineConfig const& config) { return configvar; })); + +#define INT_PROXY(number, name, configvar) \ + int_proxies.emplace_back( \ + std::make_unique>(number, name, [](MachineConfig const& config) { return configvar; })); + void make_settings() { Setting::init(); @@ -64,4 +80,32 @@ void make_settings() { start_message = new StringSetting("Message issued at startup", EXTENDED, WG, NULL, "Start/Message", "Grbl \\V [FluidNC \\B (\\R) \\H]", 0, 40, NULL); + + // Some gcode senders expect Grbl to report certain numbered settings to improve + // their reporting. The following macros set up various legacy numbered Grbl settings, + // which are derived from MachineConfig settings. + + // 130-132: Max travel (mm) + FLOAT_PROXY("130", "Grbl/MaxTravel/X", config._axes->_axis[0]->_maxTravel) + FLOAT_PROXY("131", "Grbl/MaxTravel/Y", config._axes->_axis[1]->_maxTravel) + FLOAT_PROXY("132", "Grbl/MaxTravel/Z", config._axes->_axis[2]->_maxTravel) + + // 120-122: Acceleration (mm/sec^2) + FLOAT_PROXY("120", "Grbl/Acceleration/X", config._axes->_axis[0]->_acceleration) + FLOAT_PROXY("121", "Grbl/Acceleration/Y", config._axes->_axis[1]->_acceleration) + FLOAT_PROXY("122", "Grbl/Acceleration/Z", config._axes->_axis[2]->_acceleration) + + // 110-112: Max rate (mm/min) + FLOAT_PROXY("110", "Grbl/MaxRate/X", config._axes->_axis[0]->_maxRate) + FLOAT_PROXY("111", "Grbl/MaxRate/Y", config._axes->_axis[1]->_maxRate) + FLOAT_PROXY("112", "Grbl/MaxRate/Z", config._axes->_axis[2]->_maxRate) + + // 100-102: Resolution (steps/mm) + FLOAT_PROXY("100", "Grbl/Resolution/X", config._axes->_axis[0]->_stepsPerMm) + FLOAT_PROXY("101", "Grbl/Resolution/Y", config._axes->_axis[1]->_stepsPerMm) + FLOAT_PROXY("102", "Grbl/Resolution/Z", config._axes->_axis[2]->_stepsPerMm) + + INT_PROXY("20", "Grbl/SoftLimitsEnable", config._axes->_axis[0]->_softLimits) + INT_PROXY("21", "Grbl/HardLimitsEnable", config._axes->hasHardLimits()) + INT_PROXY("22", "Grbl/HomingCycleEnable", (bool)Axes::homingMask) } diff --git a/FluidNC/src/Spindles/HuanyangSpindle.cpp b/FluidNC/src/Spindles/HuanyangSpindle.cpp index 7664ca33a..d68947b60 100644 --- a/FluidNC/src/Spindles/HuanyangSpindle.cpp +++ b/FluidNC/src/Spindles/HuanyangSpindle.cpp @@ -243,7 +243,7 @@ namespace Spindles { auto huanyang = static_cast(vfd); huanyang->_minFrequency = value; - log_info(huanyang->name() << " PD005,PD011 Freq range (" << (huanyang->_minFrequency / 100) << "," + log_info(huanyang->name() << " PD0011, PD005 Freq range (" << (huanyang->_minFrequency / 100) << "," << (huanyang->_maxFrequency / 100) << ") Hz" << " (" << (huanyang->_minFrequency / 100 * 60) << "," << (huanyang->_maxFrequency / 100 * 60) << ") RPM"); diff --git a/FluidNC/src/Spindles/Spindle.cpp b/FluidNC/src/Spindles/Spindle.cpp index fa617f8e7..eefc09aea 100644 --- a/FluidNC/src/Spindles/Spindle.cpp +++ b/FluidNC/src/Spindles/Spindle.cpp @@ -103,6 +103,14 @@ namespace Spindles { _speeds.push_back({ max, 100.0f }); } + uint32_t Spindle::maxSpeed() { + if (_speeds.size() == 0) { + return 0; + } else { + return _speeds[_speeds.size() - 1].speed; + } + } + uint32_t IRAM_ATTR Spindle::mapSpeed(SpindleSpeed speed) { if (_speeds.size() == 0) { return 0; diff --git a/FluidNC/src/Spindles/Spindle.h b/FluidNC/src/Spindles/Spindle.h index ccf5d3255..85e7be5e6 100644 --- a/FluidNC/src/Spindles/Spindle.h +++ b/FluidNC/src/Spindles/Spindle.h @@ -31,7 +31,7 @@ namespace Spindles { bool _defaultedSpeeds; uint32_t offSpeed() { return _speeds[0].offset; } - uint32_t maxSpeed() { return _speeds[_speeds.size() - 1].speed; } + uint32_t maxSpeed(); uint32_t mapSpeed(SpindleSpeed speed); void setupSpeeds(uint32_t max_dev_speed); void shelfSpeeds(SpindleSpeed min, SpindleSpeed max); diff --git a/FluidNC/src/Spindles/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index e198d3488..9965eb4c4 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -20,10 +20,11 @@ */ #include "VFDSpindle.h" -#include "../Machine/MachineConfig.h" -#include "../MotionControl.h" // mc_reset -#include "../Protocol.h" // rtAlarm -#include "../Report.h" // hex message +#include "src/Machine/MachineConfig.h" +#include "src/MotionControl.h" // mc_critical +#include "src/Protocol.h" // rtAlarm +#include "src/Report.h" // hex message +#include "src/Configuration/HandlerType.h" #include #include @@ -244,9 +245,8 @@ namespace Spindles { pollidx = -1; } if (next_cmd.critical) { + mc_critical(ExecAlarm::SpindleControl); log_error("Critical VFD RS485 Unresponsive"); - mc_reset(); - rtAlarm = ExecAlarm::SpindleControl; } } } @@ -365,9 +365,8 @@ namespace Spindles { #endif if (unchanged == limit) { + mc_critical(ExecAlarm::SpindleControl); log_error(name() << " spindle did not reach device units " << dev_speed << ". Reported value is " << _sync_dev_speed); - mc_reset(); - rtAlarm = ExecAlarm::SpindleControl; } _syncing = false; @@ -417,9 +416,9 @@ namespace Spindles { action.action = actionSetSpeed; action.arg = dev_speed; action.critical = (dev_speed == 0); - if (xQueueSendFromISR(vfd_cmd_queue, &action, 0) != pdTRUE) { - log_info("VFD Queue Full"); - } + // Ignore errors because reporting is not safe from an ISR. + // Perhaps set a flag instead? + xQueueSendFromISR(vfd_cmd_queue, &action, 0); } } @@ -476,4 +475,24 @@ namespace Spindles { return crc; } + void VFD::validate() { + Spindle::validate(); + Assert(_uart != nullptr || _uart_num != -1, "VFD: missing UART configuration"); + } + + void VFD::group(Configuration::HandlerBase& handler) { + if (handler.handlerType() == Configuration::HandlerType::Generator) { + if (_uart_num == -1) { + handler.section("uart", _uart, 1); + } else { + handler.item("uart_num", _uart_num); + } + } else { + handler.section("uart", _uart, 1); + handler.item("uart_num", _uart_num); + } + handler.item("modbus_id", _modbus_id, 0, 247); // per https://modbus.org/docs/PI_MBUS_300.pdf + + Spindle::group(handler); + } } diff --git a/FluidNC/src/Spindles/VFDSpindle.h b/FluidNC/src/Spindles/VFDSpindle.h index d7f0aa816..58169134b 100644 --- a/FluidNC/src/Spindles/VFDSpindle.h +++ b/FluidNC/src/Spindles/VFDSpindle.h @@ -94,19 +94,8 @@ namespace Spindles { SpindleSpeed _slop; // Configuration handlers: - void validate() override { - Spindle::validate(); - Assert(_uart != nullptr || _uart_num != -1, "VFD: missing UART configuration"); - Assert(!(_uart != nullptr && _uart_num != -1), "VFD: conflicting UART configuration"); - } - - void group(Configuration::HandlerBase& handler) override { - handler.section("uart", _uart, 1); - handler.item("uart_num", _uart_num); - handler.item("modbus_id", _modbus_id, 0, 247); // per https://modbus.org/docs/PI_MBUS_300.pdf - - Spindle::group(handler); - } + void validate() override; + void group(Configuration::HandlerBase& handler) override; virtual ~VFD() {} }; diff --git a/FluidNC/src/StartupLog.cpp b/FluidNC/src/StartupLog.cpp deleted file mode 100644 index 0e36e71fb..000000000 --- a/FluidNC/src/StartupLog.cpp +++ /dev/null @@ -1,21 +0,0 @@ -#include "StartupLog.h" -#include -#include "Protocol.h" // send_line() - -size_t StartupLog::write(uint8_t data) { - _messages += (char)data; - return 1; -} -std::string StartupLog::messages() { - return _messages; -} -void StartupLog::dump(Channel& out) { - std::istringstream iss(_messages); - for (std::string line; std::getline(iss, line);) { - log_to(out, line); - } -} - -StartupLog::~StartupLog() {} - -StartupLog startupLog("Startup Log"); diff --git a/FluidNC/src/StartupLog.h b/FluidNC/src/StartupLog.h index 51176a2e8..fd678f127 100644 --- a/FluidNC/src/StartupLog.h +++ b/FluidNC/src/StartupLog.h @@ -6,19 +6,16 @@ #include "Config.h" #include "Channel.h" -#include class StartupLog : public Channel { -private: - std::string _messages; - public: - StartupLog(const char* name) : Channel(name) {} + StartupLog() : Channel("Startup Log") {} virtual ~StartupLog(); - size_t write(uint8_t data) override; - std::string messages(); - void dump(Channel& channel); + size_t write(uint8_t data) override; + + static void init(); + static void dump(Channel& channel); }; extern StartupLog startupLog; diff --git a/FluidNC/src/Status_outputs.cpp b/FluidNC/src/Status_outputs.cpp new file mode 100644 index 000000000..d6a468809 --- /dev/null +++ b/FluidNC/src/Status_outputs.cpp @@ -0,0 +1,77 @@ +// Copyright (c) 2023 - Bart Dring +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +/* + This is a class for status "Idle,Run,Hold,Alarm" pins. + + This can be used for Tower lights,etc. +*/ +#include "Status_outputs.h" +#include "Machine/MachineConfig.h" + +void Status_Outputs::init() { + if (_Idle_pin.defined()) { + _Idle_pin.setAttr(Pin::Attr::Output); + } + + if (_Run_pin.defined()) { + _Run_pin.setAttr(Pin::Attr::Output); + } + + if (_Hold_pin.defined()) { + _Hold_pin.setAttr(Pin::Attr::Output); + } + + if (_Alarm_pin.defined()) { + _Alarm_pin.setAttr(Pin::Attr::Output); + } + + log_info("Status outputs" + << " Interval:" << _report_interval_ms << " Idle:" << _Idle_pin.name() << " Cycle:" << _Run_pin.name() + << " Hold:" << _Hold_pin.name() << " Alarm:" << _Alarm_pin.name()); + + allChannels.registration(this); + setReportInterval(_report_interval_ms); +} + +void Status_Outputs::parse_report() { + if (_report.rfind("<", 0) == 0) { + parse_status_report(); + return; + } +} + +// This is how the OLED driver receives channel data +size_t Status_Outputs::write(uint8_t data) { + char c = data; + if (c == '\r') { + return 1; + } + if (c == '\n') { + parse_report(); + _report = ""; + return 1; + } + _report += c; + return 1; +} + +Channel* Status_Outputs::pollLine(char* line) { + autoReport(); + return nullptr; +} + +void Status_Outputs::parse_status_report() { + if (_report.back() == '>') { + _report.pop_back(); + } + // Now the string is a sequence of field|field|field + size_t pos = 0; + auto nextpos = _report.find_first_of("|", pos); + _state = _report.substr(pos + 1, nextpos - pos - 1); + + _Idle_pin.write(_state == "Idle"); + _Run_pin.write(_state == "Run"); + _Hold_pin.write(_state.substr(0, 4) == "Hold"); + _Alarm_pin.write(_state == "Alarm"); +} diff --git a/FluidNC/src/Status_outputs.h b/FluidNC/src/Status_outputs.h new file mode 100644 index 000000000..1ef334ee7 --- /dev/null +++ b/FluidNC/src/Status_outputs.h @@ -0,0 +1,56 @@ +#pragma once + +#include "Config.h" +#include "Configuration/Configurable.h" +#include "Channel.h" + +typedef const uint8_t* font_t; + +class Status_Outputs : public Channel, public Configuration::Configurable { + Pin _Idle_pin; + Pin _Run_pin; + Pin _Hold_pin; + Pin _Alarm_pin; + +public: +private: + std::string _report; + std::string _state; + + int _report_interval_ms = 500; + + void parse_report(); + void parse_status_report(); + +public: + Status_Outputs() : Channel("status_outputs") {} + + Status_Outputs(const Status_Outputs&) = delete; + Status_Outputs(Status_Outputs&&) = delete; + Status_Outputs& operator=(const Status_Outputs&) = delete; + Status_Outputs& operator=(Status_Outputs&&) = delete; + + virtual ~Status_Outputs() = default; + + void init(); + + size_t write(uint8_t data) override; + + Channel* pollLine(char* line) override; + void flushRx() override {} + + bool lineComplete(char*, char) override { return false; } + size_t timedReadBytes(char* buffer, size_t length, TickType_t timeout) override { return 0; } + + // Configuration handlers: + void validate() override {} + void afterParse() override {}; + + void group(Configuration::HandlerBase& handler) override { + handler.item("report_interval_ms", _report_interval_ms, 100, 5000); + handler.item("idle_pin", _Idle_pin); + handler.item("run_pin", _Run_pin); + handler.item("hold_pin", _Hold_pin); + handler.item("alarm_pin", _Alarm_pin); + } +}; diff --git a/FluidNC/src/Stepping.cpp b/FluidNC/src/Stepping.cpp index d677cfd6f..631c47687 100644 --- a/FluidNC/src/Stepping.cpp +++ b/FluidNC/src/Stepping.cpp @@ -138,7 +138,7 @@ namespace Machine { handler.item("idle_ms", _idleMsecs, 0, 10000000); // full range handler.item("pulse_us", _pulseUsecs, 0, 30); handler.item("dir_delay_us", _directionDelayUsecs, 0, 10); - handler.item("disable_delay_us", _disableDelayUsecs, 0, 10); + handler.item("disable_delay_us", _disableDelayUsecs, 0, 1000000); // max 1 second handler.item("segments", _segments, 6, 20); } diff --git a/FluidNC/src/StringRange.h b/FluidNC/src/StringRange.h deleted file mode 100644 index 9e81c74a0..000000000 --- a/FluidNC/src/StringRange.h +++ /dev/null @@ -1,144 +0,0 @@ -// Copyright (c) 2021 Stefan de Bruijn -// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. - -#pragma once - -#include - -class StringRange { - const char* start_; - const char* end_; - -public: - StringRange() : start_(nullptr), end_(nullptr) {} - - StringRange(const char* str) : start_(str), end_(str + strlen(str)) {} - - StringRange(const char* start, const char* end) : start_(start), end_(end) {} - - StringRange(const StringRange& o) = default; - StringRange(StringRange&& o) = default; - - StringRange& operator=(const StringRange& o) = default; - StringRange& operator=(StringRange&& o) = default; - inline bool operator==(const char* s) { - const char* p = start_; - while (p != end_ && *s) { - if (::tolower(*p++) != ::tolower(*s++)) { - return false; - } - } - return !*s && p == end_; - } - inline bool operator!=(const char* s) { - const char* p = start_; - while (p != end_ && *s) { - if (::tolower(*p++) != ::tolower(*s++)) { - return true; - } - } - return *s || p != end_; - } - - int find(char c) const { - const char* s = start_; - for (; s != end_ && *s != c; ++s) {} - return (*s) ? (s - start_) : -1; - } - - StringRange substr(int index, int length) const { - const char* s = start_ + index; - if (s > end_) { - s = end_; - } - const char* e = s + length; - if (e > end_) { - e = end_; - } - return StringRange(s, e); - } - - // Blank-delimited word - StringRange nextWord() { - while (start_ != end_ && *start_ == ' ') { - ++start_; - } - const char* s = start_; - while (start_ != end_ && *start_ != ' ') { - ++start_; - } - return StringRange(s, start_); - } - - // Character-delimited word - StringRange nextWord(char c) { - const char* s = start_; - // Scan to delimiter or end of string - while (start_ != end_ && *start_ != c) { - ++start_; - } - const char* e = start_; - // Skip the delimiter if present - if (start_ != end_) { - ++start_; - } - return StringRange(s, e); - } - - bool equals(const StringRange& o) const { - auto l = length(); - return l == o.length() && !strncasecmp(start_, o.start_, l); - } - - bool equals(const char* o) const { - const char* c = start_; - const char* oc = o; - for (; c != end_ && *oc != '\0' && tolower(*c) == tolower(*oc); ++c, ++oc) {} - return c == end_ && *oc == '\0'; - } - - int length() const { return end_ - start_; } - - // Iterator support: - const char* begin() const { return start_; } - const char* end() const { return end_; } - - std::string str() const { - // TODO: Check if we can eliminate this function. I'm pretty sure we can. - auto len = length(); - if (len == 0) { - return std::string(); - } else { - char* buf = new char[len + 1]; - memcpy(buf, begin(), len); - buf[len] = 0; - std::string tmp(buf); - delete[] buf; - return tmp; - } - } - - inline bool isUInteger(uint32_t& intval) { - char* intEnd; - intval = strtol(start_, &intEnd, 10); - return intEnd == end_; - } - - inline bool isInteger(int32_t& intval) { - char* intEnd; - intval = strtol(start_, &intEnd, 10); - return intEnd == end_; - } - - inline bool isUnsignedInteger(uint32_t& intval) { - char* intEnd; - intval = strtoul(start_, &intEnd, 10); - return intEnd == end_; - } - - inline bool isFloat(float& floatval) { - char* floatEnd; - floatval = float(strtod(start_, &floatEnd)); - return floatEnd == end_; - } -}; diff --git a/FluidNC/src/StringStream.h b/FluidNC/src/StringStream.h index 61a00161c..302f93c1f 100644 --- a/FluidNC/src/StringStream.h +++ b/FluidNC/src/StringStream.h @@ -4,7 +4,6 @@ #pragma once #include "Print.h" -#include "StringRange.h" #include @@ -16,6 +15,4 @@ class StringStream : public Print { data_.push_back(c); return 1; } - - // StringRange str() const { return StringRange(data_.data(), data_.data() + data_.size()); } }; diff --git a/FluidNC/src/System.cpp b/FluidNC/src/System.cpp index cc97938db..de7b57f2c 100644 --- a/FluidNC/src/System.cpp +++ b/FluidNC/src/System.cpp @@ -21,8 +21,10 @@ int32_t probe_steps[MAX_N_AXIS]; // Last probe position in steps. void system_reset() { // Reset system variables. State prior_state = sys.state; + bool prior_abort = sys.abort; memset(&sys, 0, sizeof(system_t)); // Clear system struct variable. sys.state = prior_state; + sys.abort = prior_abort; sys.f_override = FeedOverride::Default; // Set to 100% sys.r_override = RapidOverride::Default; // Set to 100% sys.spindle_speed_ovr = SpindleSpeedOverride::Default; // Set to 100% diff --git a/FluidNC/src/Types.h b/FluidNC/src/Types.h index 54cb3907b..b0b9ef9b1 100644 --- a/FluidNC/src/Types.h +++ b/FluidNC/src/Types.h @@ -20,4 +20,5 @@ enum class State : uint8_t { SafetyDoor, // Safety door is ajar. Feed holds and de-energizes system. Sleep, // Sleep state. ConfigAlarm, // You can't do anything but fix your config file. + Critical, // You can't do anything but reset with CTRL-x or the reset button }; diff --git a/FluidNC/src/UTF8.cpp b/FluidNC/src/UTF8.cpp new file mode 100644 index 000000000..54cebfc21 --- /dev/null +++ b/FluidNC/src/UTF8.cpp @@ -0,0 +1,177 @@ +// Copyright (c) 2021 - Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#define PASS_THROUGH_80_BF +// #define TEST_UTF8 + +#include "UTF8.h" + +// Returns 1 if we have a valid sequence, and value is set +// Returns 0 if we are in the middle of a sequence +// Returns -1 if there is a sequence error +int UTF8::decode(uint8_t ch, uint32_t& value) { + if (_state) { + if ((ch & 0xc0) != 0x80) { + // Trailing bytes in a sequence must have 10 in the two high bits + _state = 0; + return -1; + } + // Otherwise, ch is between 0x80 and 0xbf, so it is the + // second, third, or fourth byte of a UTF8 sequence + _state--; + _num = (_num << 6) | (ch & 0x3f); + if (_state) { + return 0; + } + value = _num; + return 1; + } + // After this point, _state is zero + if (ch < 0x80) { + // 1-byte sequence - No decoding necessary + value = ch; + return 1; + } +#ifdef PASS_THROUGH_80_BF + if (ch < 0xbf) { + // UTF8 uses 0x80-0xbf only for continuation bytes, i.e. the second, + // third, or fourth byte of a sequence. Therefore, a byte in that + // range should be an error if it occurs outside of a sequence. + // But GRBL uses that range for realtime characters, and all + // preexisting GRBL serial senders send such bytes unencoded. + // By passing them through without an error, we can be backwards + // compatible. + value = ch; + return 1; + } +#endif + + if (ch >= 0xf0) { + _state = 3; // Start of 4-byte sequence + _num = ch & 0x07; + return 0; + } + if (ch >= 0xe0) { + _state = 2; // Start of 3-byte sequence + _num = ch & 0x0f; + return 0; + } + if (ch >= 0xc0) { + _state = 1; // Start of 2-byte sequence + _num = ch & 0x1f; + return 0; + } + // Otherwise we received a continuation byte with the two high bits == 10, + // i.e. ch between 0x80 and 0xbf, when not in the midst of a sequence + return -1; +} +bool UTF8::decode(const std::vector& input, uint32_t& value) { + int len = input.size(); + for (auto& ch : input) { + --len; + int result = decode(ch, value); + if (result == -1) { + return false; + } + if (result == 1) { + return len == 0; // Error if there are more bytes in the input + } + } + // Reached end of input without finishing the decode + return false; +} +std::vector UTF8::encode(const uint32_t value) { + std::vector output; + if (value >= 0x110000) { + // In this case, the returned vector will be empty + return output; + } + if (value >= 0x100000) { + output.push_back(0xf0 | ((value >> 18) & 0x07)); + output.push_back(0x80 | ((value >> 12) & 0x3f)); + output.push_back(0x80 | ((value >> 6) & 0x3f)); + output.push_back(0x80 | (value & 0x3f)); + return output; + } + if (value >= 0x800) { + output.push_back(0xe0 | ((value >> 12) & 0x0f)); + output.push_back(0x80 | ((value >> 6) & 0x3f)); + output.push_back(0x80 | (value & 0x3f)); + return output; + } + if (value >= 0x80) { + output.push_back(0xc0 | ((value >> 6) & 0x01f)); + output.push_back(0x80 | (value & 0x3f)); + return output; + } + output.push_back(value); + return output; +} + +#ifdef TEST_UTF8 +# include + +static bool decode_test(UTF8* utf8, std::vector input, uint32_t& value) { + for (auto& ch : input) { + printf("%x ", ch); + } + printf("-> "); + auto res = utf8->decode(input, value); + if (res) { + printf("%x\n", value); + } else { + printf("ERROR\n"); + } + return res; +} + +static bool encode_test(UTF8* utf8, uint32_t value) { + auto encoded = utf8->encode(value); + printf("%x -> ", value); + if (encoded.size()) { + uint32_t out_value; + bool res = decode_test(utf8, encoded, out_value); + if (!res) { + return false; + } + if (out_value != value) { + printf(" -- Incorrect value\n"); + return false; + } + return true; + } else { + printf("ERROR\n"); + return false; + } +} + +void test_UTF8() { + UTF8* utf8 = new UTF8(); + encode_test(utf8, 0x7f); + encode_test(utf8, 0x80); + encode_test(utf8, 0x90); + encode_test(utf8, 0xa0); + encode_test(utf8, 0xbf); + encode_test(utf8, 0x100); + encode_test(utf8, 0x13f); + encode_test(utf8, 0x140); + encode_test(utf8, 0x17f); + encode_test(utf8, 0x1ff); + encode_test(utf8, 0x200); + encode_test(utf8, 0x2ff); + encode_test(utf8, 0x7ff); + encode_test(utf8, 0x800); + encode_test(utf8, 0xffff); + encode_test(utf8, 0x100000); + encode_test(utf8, 0x10ffff); + encode_test(utf8, 0x110000); + uint32_t out_value; + decode_test(utf8, std::vector { 0x80 }, out_value); // continuation byte outside + decode_test(utf8, std::vector { 0xc0 }, out_value); // Incomplete sequence + decode_test(utf8, std::vector { 0xc0, 0x30 }, out_value); // Non-continuation inside + decode_test(utf8, std::vector { 0xc0, 0x80, 0x30 }, out_value); // Extra bytes + delete utf8; +} +#else +void test_UTF8() {} +#endif diff --git a/FluidNC/src/UTF8.h b/FluidNC/src/UTF8.h new file mode 100644 index 000000000..8786ed94a --- /dev/null +++ b/FluidNC/src/UTF8.h @@ -0,0 +1,26 @@ +// Copyright (c) 2021 - Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#pragma once + +#include +#include + +class UTF8 { +private: + uint32_t _num; + int _state = 0; + +public: + // Byte-at-a-time decoder. Returns -1 for error, 1 for okay, 0 for keep trying + int decode(uint8_t ch, uint32_t& value); + + // Vector-of-bytes decoder. Returns true if the vector contains + // a well-formed UTF8 sequence. + bool decode(const std::vector& in, uint32_t& value); + + // Encode to vector + std::vector encode(const uint32_t value); +}; + +void test_UTF8(); diff --git a/FluidNC/src/Uart.cpp b/FluidNC/src/Uart.cpp index 5e31104b3..68de4e2c4 100644 --- a/FluidNC/src/Uart.cpp +++ b/FluidNC/src/Uart.cpp @@ -20,6 +20,7 @@ static void uart_driver_n_install(void* arg) { void Uart::begin(unsigned long baud, UartData dataBits, UartStop stopBits, UartParity parity) { // uart_driver_delete(_uart_num); uart_config_t conf; + conf.source_clk = UART_SCLK_APB; conf.baud_rate = baud; conf.data_bits = uart_word_length_t(_dataBits); conf.parity = uart_parity_t(_parity); diff --git a/FluidNC/src/UartChannel.cpp b/FluidNC/src/UartChannel.cpp index f304f8802..7520a52a9 100644 --- a/FluidNC/src/UartChannel.cpp +++ b/FluidNC/src/UartChannel.cpp @@ -5,7 +5,7 @@ #include "Machine/MachineConfig.h" // config #include "Serial.h" // allChannels -UartChannel::UartChannel(bool addCR) : Channel("uart", addCR) { +UartChannel::UartChannel(int num, bool addCR) : Channel("uart_channel", num, addCR) { _lineedit = new Lineedit(this, _line, Channel::maxLine - 1); } @@ -16,10 +16,19 @@ void UartChannel::init() { } else { log_error("UartChannel: missing uart" << _uart_num); } + setReportInterval(_report_interval_ms); } void UartChannel::init(Uart* uart) { _uart = uart; allChannels.registration(this); + if (_report_interval_ms) { + log_info("uart_channel" << _uart_num << " created at report interval: " << _report_interval_ms); + } else { + log_info("uart_channel" << _uart_num << " created"); + } + log_msg_to(*this, "RST"); + // Give the extender a little time to process the command + delay(100); } size_t UartChannel::write(uint8_t c) { @@ -115,7 +124,7 @@ size_t UartChannel::timedReadBytes(char* buffer, size_t length, TickType_t timeo return length - remlen; } -UartChannel Uart0(true); // Primary serial channel with LF to CRLF conversion +UartChannel Uart0(0, true); // Primary serial channel with LF to CRLF conversion void uartInit() { auto uart0 = new Uart(0); diff --git a/FluidNC/src/UartChannel.h b/FluidNC/src/UartChannel.h index 94f9aec5f..faaebe67f 100644 --- a/FluidNC/src/UartChannel.h +++ b/FluidNC/src/UartChannel.h @@ -12,10 +12,11 @@ class UartChannel : public Channel, public Configuration::Configurable { Lineedit* _lineedit; Uart* _uart; - int _uart_num = 0; + int _uart_num = 0; + int _report_interval_ms = 0; public: - UartChannel(bool addCR = false); + UartChannel(int num, bool addCR = false); void init(); void init(Uart* uart); @@ -39,7 +40,11 @@ class UartChannel : public Channel, public Configuration::Configurable { Channel* pollLine(char* line) override; // Configuration methods - void group(Configuration::HandlerBase& handler) override { handler.item("uart_num", _uart_num); } + void group(Configuration::HandlerBase& handler) override { + handler.item("report_interval_ms", _report_interval_ms); + handler.item("uart_num", _uart_num); + handler.item("message_level", _message_level, messageLevels2); + } }; extern UartChannel Uart0; diff --git a/FluidNC/src/WebUI/BTConfig.cpp b/FluidNC/src/WebUI/BTConfig.cpp index 25a7a6737..fdcecb12d 100644 --- a/FluidNC/src/WebUI/BTConfig.cpp +++ b/FluidNC/src/WebUI/BTConfig.cpp @@ -10,11 +10,14 @@ # include "Commands.h" // COMMANDS # include "WebSettings.h" +# include "esp_bt.h" +# include "esp_bt_main.h" + # include // SerialBT sends the data over Bluetooth namespace WebUI { - BTConfig bt_config; + BTConfig bt_config __attribute__((init_priority(105))) ; BluetoothSerial SerialBT; BTChannel btChannel; } @@ -148,6 +151,13 @@ namespace WebUI { return Channel::pollLine(line); } + void BTConfig::releaseMem() { + log_debug("Releasing Bluetooth memory"); + esp_bt_mem_release(ESP_BT_MODE_CLASSIC_BT); + esp_bt_mem_release(ESP_BT_MODE_BLE); + log_debug("Heap: " << xPortGetFreeHeapSize()); + } + /** * begin WiFi setup */ @@ -158,25 +168,23 @@ namespace WebUI { //stop active services end(); - if (!bt_enable->get()) { - log_info("Bluetooth not enabled"); - return false; - } - + log_debug("Heap: " << xPortGetFreeHeapSize()); _btname = bt_name->getStringValue(); - - if (_btname.length()) { + if (bt_enable->get() && _btname.length()) { + esp_bt_mem_release(ESP_BT_MODE_BLE); + log_debug("Heap: " << xPortGetFreeHeapSize()); if (!SerialBT.begin(_btname.c_str())) { log_error("Bluetooth failed to start"); return false; } + SerialBT.register_callback(&my_spp_cb); log_info("BT Started with " << _btname); allChannels.registration(&btChannel); return true; } + releaseMem(); log_info("BT is not enabled"); - end(); return false; } diff --git a/FluidNC/src/WebUI/BTConfig.h b/FluidNC/src/WebUI/BTConfig.h index 3e030472e..125231c83 100644 --- a/FluidNC/src/WebUI/BTConfig.h +++ b/FluidNC/src/WebUI/BTConfig.h @@ -13,6 +13,7 @@ namespace WebUI { static bool begin() { return false; }; static void end() {}; static void handle() {} + static void releaseMem() {} static bool isOn() { return false; } }; extern BTConfig bt_config; @@ -85,6 +86,7 @@ namespace WebUI { void handle(); void reset_settings(); bool isOn() const; + void releaseMem(); ~BTConfig(); }; diff --git a/FluidNC/src/WebUI/JSONEncoder.cpp b/FluidNC/src/WebUI/JSONEncoder.cpp index c2998c5fa..4ea1f6128 100644 --- a/FluidNC/src/WebUI/JSONEncoder.cpp +++ b/FluidNC/src/WebUI/JSONEncoder.cpp @@ -7,19 +7,13 @@ namespace WebUI { // Constructor. If _pretty is true, newlines are // inserted into the JSON string for easy reading. - JSONencoder::JSONencoder(bool pretty, Channel* channel) : pretty(pretty), level(0), _channel(channel), category("nvs") { + JSONencoder::JSONencoder(bool pretty, Channel* channel) : pretty(pretty), level(0), _str(&linebuf), _channel(channel), category("nvs") { count[level] = 0; } JSONencoder::JSONencoder(bool pretty, std::string* str) : pretty(pretty), level(0), _str(str), category("nvs") { count[level] = 0; } - void JSONencoder::add(char c) { - if (_str) { - (*_str) += c; - } else { - linebuf += c; - } - } + void JSONencoder::add(char c) { (*_str) += c; } // Private function to add commas between // elements as needed, omitting the comma @@ -100,23 +94,25 @@ namespace WebUI { // Private function to increment the nesting level. void JSONencoder::dec_level() { --level; } + void JSONencoder::indent() { + for (int i = 0; i < 2 * level; i++) { + add(' '); + } + } + // Private function to implement pretty-printing void JSONencoder::line() { - if (_str) { + if (_channel) { + // log_to() always adds a newline + // We want that for channels because they might not + // be able to handle really long lines. + log_to(*_channel, *_str); + *_str = ""; + indent(); + } else { if (pretty) { add('\n'); - linebuf = ""; - for (int i = 0; i < 2 * level; i++) { - add(' '); - } - } - } else { - // Always pretty print to a channel, because channels - // cannot necessary handle really long lines. - log_to(*_channel, linebuf); - linebuf = ""; - for (int i = 0; i < 2 * level; i++) { - add(' '); + indent(); } } } @@ -153,6 +149,16 @@ namespace WebUI { add(']'); } + // Begins the creation of a member whose value is an object. + // Call end_object() to close the member + void JSONencoder::begin_member_object(const char* tag) { + comma_line(); + quoted(tag); + add(':'); + add('{'); + inc_level(); + } + // Starts an object with {. // If you need a named object you must call begin_member() first. void JSONencoder::begin_object() { diff --git a/FluidNC/src/WebUI/JSONEncoder.h b/FluidNC/src/WebUI/JSONEncoder.h index 8d80a8330..e5444ff74 100644 --- a/FluidNC/src/WebUI/JSONEncoder.h +++ b/FluidNC/src/WebUI/JSONEncoder.h @@ -19,8 +19,12 @@ namespace WebUI { void quoted(const char* s); void inc_level(); void dec_level(); + void indent(); void line(); + // begin_member() starts the creation of a member. + void begin_member(const char* tag); + std::string linebuf; std::string* _str = nullptr; @@ -57,10 +61,9 @@ namespace WebUI { // end_object() closes the object with } void end_object(); - // begin_member() starts the creation of a member. - // The only case where you need to use it directly - // is when you want a member whose value is an object. - void begin_member(const char* tag); + // Begins the creation of a member whose value is an object. + // Call end_object() to close the member + void begin_member_object(const char* tag); // The begin_webui() methods are specific to Esp3D_WebUI // WebUI sends JSON objects to the UI to generate configuration diff --git a/FluidNC/src/WebUI/NotificationsService.cpp b/FluidNC/src/WebUI/NotificationsService.cpp index c1a5a1e6c..f03281553 100644 --- a/FluidNC/src/WebUI/NotificationsService.cpp +++ b/FluidNC/src/WebUI/NotificationsService.cpp @@ -15,7 +15,7 @@ #include "NotificationsService.h" namespace WebUI { - NotificationsService notificationsService; + NotificationsService notificationsService __attribute__((init_priority(106))) ; } #ifdef ENABLE_WIFI @@ -142,11 +142,21 @@ namespace WebUI { break; } delay_ms(10); + log_verbose("Received: '" << answer << "' (waiting 4 '" << expected_answer << "')"); } if (strlen(expected_answer) == 0) { return true; } - return answer.find(expected_answer) != std::string::npos; + + bool result = answer.find(expected_answer) != std::string::npos; + if (!result) { + if (answer.length()) { + log_debug("Received: '" << answer << "' (expected: '" << expected_answer << "')"); + } else { + log_debug("No answer (expected: " << expected_answer << ")"); + } + } + return result; } return false; } @@ -221,11 +231,26 @@ namespace WebUI { Notificationclient.stop(); return res; } + bool NotificationsService::sendEmailMSG(const char* title, const char* message) { WiFiClientSecure Notificationclient; + // Switch off secure mode because the connect command always fails in secure mode:( + Notificationclient.setInsecure(); + if (!Notificationclient.connect(_serveraddress.c_str(), _port)) { + //Read & log error message (in debug mode) + if (atMsgLevel(MsgLevelDebug)) { + char errMsg[150]; + const int lastError = Notificationclient.lastError(errMsg, sizeof(errMsg)); + if (0 == lastError) { + errMsg[0] = 0; + } + log_debug("Cannot connect to " << _serveraddress.c_str() << ":" << _port << ", err: " << lastError << " - " << errMsg); + } return false; } + log_verbose("Connected to " << _serveraddress.c_str() << ":" << _port); + //Check answer of connection if (!Wait4Answer(Notificationclient, "220", "220", EMAILTIMEOUT)) { return false; @@ -333,7 +358,7 @@ namespace WebUI { } //TODO add a check for valid email ? - _serveraddress = tmp.substr(pos1 + 1, pos2); + _serveraddress = tmp.substr(pos1 + 1, pos2 - pos1 - 1); return true; } //Email#serveraddress:port diff --git a/FluidNC/src/WebUI/TelnetServer.cpp b/FluidNC/src/WebUI/TelnetServer.cpp index 213f3b33e..3d82381e2 100644 --- a/FluidNC/src/WebUI/TelnetServer.cpp +++ b/FluidNC/src/WebUI/TelnetServer.cpp @@ -9,7 +9,7 @@ #ifdef ENABLE_WIFI namespace WebUI { - TelnetServer telnetServer; + TelnetServer telnetServer __attribute__((init_priority(107))); } # include "WifiServices.h" @@ -50,7 +50,9 @@ namespace WebUI { _setupdone = true; //add mDNS - MDNS.addService("telnet", "tcp", _port); + if (WebUI::wifi_sta_ssdp->get()) { + MDNS.addService("telnet", "tcp", _port); + } return no_error; } diff --git a/FluidNC/src/WebUI/WSChannel.cpp b/FluidNC/src/WebUI/WSChannel.cpp index ea7e7857a..df9220406 100644 --- a/FluidNC/src/WebUI/WSChannel.cpp +++ b/FluidNC/src/WebUI/WSChannel.cpp @@ -8,11 +8,17 @@ # include # include +# include "../Serial.h" // is_realtime_command + namespace WebUI { - WSChannel::WSChannel(WebSocketsServer* server, uint8_t clientNum) : - Channel("websocket"), _server(server), _clientNum(clientNum), _TXbufferSize(0), _RXbufferSize(0), _RXbufferpos(0) {} + class WSChannels; + + WSChannel::WSChannel(WebSocketsServer* server, uint8_t clientNum) : Channel("websocket"), _server(server), _clientNum(clientNum) {} int WSChannel::read() { + if (_dead) { + return -1; + } if (_rtchar == -1) { return -1; } else { @@ -27,28 +33,56 @@ namespace WebUI { size_t WSChannel::write(uint8_t c) { return write(&c, 1); } size_t WSChannel::write(const uint8_t* buffer, size_t size) { - if (buffer == NULL) { + if (buffer == NULL || _dead || !size) { return 0; } - if (_TXbufferSize == 0) { - _lastflush = millis(); - } + bool complete_line = buffer[size - 1] == '\n'; + + const uint8_t* out; + size_t outlen; + if (_output_line.length() == 0 && complete_line) { + // Avoid the overhead of std::string if we the + // input is a complete line and nothing is pending. + out = buffer; + outlen = size; + } else { + // Otherwise collect input until we have line. + _output_line.append((char*)buffer, size); + if (!complete_line) { + return size; + } - for (int i = 0; i < size; i++) { - if (_TXbufferSize >= TXBUFFERSIZE) { - flush(); + out = (uint8_t*)_output_line.c_str(); + outlen = _output_line.length(); + } + int stat = _server->canSend(_clientNum); + if (stat < 0) { + _dead = true; + log_debug("WebSocket is dead; closing"); + return 0; + } + if (stat == 0) { + if (_output_line.length()) { + _output_line = ""; } - _TXbuffer[_TXbufferSize] = buffer[i]; - _TXbufferSize++; + return size; + } + if (!_server->sendBIN(_clientNum, out, outlen)) { + _dead = true; + log_debug("WebSocket is unresponsive; closing"); } - handle(); + if (_output_line.length()) { + _output_line = ""; + } + return size; } - void WSChannel::pushRT(char ch) { _rtchar = ch; } - bool WSChannel::push(const uint8_t* data, size_t length) { + if (_dead) { + return false; + } char c; while ((c = *data++) != '\0') { _queue.push(c); @@ -56,26 +90,150 @@ namespace WebUI { return true; } - bool WSChannel::push(std::string& s) { return push((uint8_t*)s.c_str(), s.length()); } + bool WSChannel::push(const std::string& s) { return push((uint8_t*)s.c_str(), s.length()); } - void WSChannel::handle() { - if (_TXbufferSize > 0 && ((_TXbufferSize >= TXBUFFERSIZE) || ((millis() - _lastflush) > FLUSHTIMEOUT))) { - flush(); + bool WSChannel::sendTXT(std::string& s) { + if (_dead) { + return false; + } + if (!_server->sendTXT(_clientNum, s.c_str())) { + _dead = true; + log_debug("WebSocket is unresponsive; closing"); + WSChannels::removeChannel(this); + return false; } + return true; } - size_t WSChannel::sendTXT(std::string& s) { return _server->sendTXT(_clientNum, s.c_str()); } - void WSChannel::flush(void) { - if (_TXbufferSize > 0) { - _server->sendBIN(_clientNum, _TXbuffer, _TXbufferSize); - //refresh timout - _lastflush = millis(); - - //reset buffer - _TXbufferSize = 0; + void WSChannel::autoReport() { + int stat = _server->canSend(_clientNum); + if (stat > 0) { + Channel::autoReport(); } } WSChannel::~WSChannel() {} + + std::map WSChannels::_wsChannels; + std::list WSChannels::_webWsChannels; + + WSChannel* WSChannels::_lastWSChannel = nullptr; + + WSChannel* WSChannels::getWSChannel(int pageid) { + WSChannel* wsChannel = nullptr; + if (pageid != -1) { + try { + wsChannel = _wsChannels.at(pageid); + } catch (std::out_of_range& oor) {} + } else { + // If there is no PAGEID URL argument, it is an old version of WebUI + // that does not supply PAGEID in all cases. In that case, we use + // the most recently used websocket if it is still in the list. + for (auto it = _wsChannels.begin(); it != _wsChannels.end(); ++it) { + if (it->second == _lastWSChannel) { + wsChannel = _lastWSChannel; + break; + } + } + } + _lastWSChannel = wsChannel; + return wsChannel; + } + + void WSChannels::removeChannel(uint8_t num) { + try { + WSChannel* wsChannel = _wsChannels.at(num); + _webWsChannels.remove(wsChannel); + allChannels.kill(wsChannel); + _wsChannels.erase(num); + } catch (std::out_of_range& oor) {} + } + + void WSChannels::removeChannel(WSChannel* channel) { + _lastWSChannel = nullptr; + _webWsChannels.remove(channel); + allChannels.kill(channel); + for (auto it = _wsChannels.cbegin(); it != _wsChannels.cend();) { + if (it->second == channel) { + it = _wsChannels.erase(it); + } else { + ++it; + } + } + } + + bool WSChannels::runGCode(int pageid, std::string& cmd) { + WSChannel* wsChannel = getWSChannel(pageid); + if (wsChannel) { + if (cmd.length()) { + bool has_error = wsChannel->push(cmd); + if (!has_error && !is_realtime_command(cmd[0]) && cmd[cmd.length() - 1] != '\n') { + has_error = !wsChannel->push("\n"); + } + return has_error; + } + } + return true; + } + + bool WSChannels::sendError(int pageid, std::string err) { + WSChannel* wsChannel = getWSChannel(pageid); + if (wsChannel) { + return !wsChannel->sendTXT(err); + } + return true; + } + void WSChannels::sendPing() { + for (WSChannel* wsChannel : _webWsChannels) { + std::string s("PING:"); + s += std::to_string(wsChannel->id()); + // sendBIN would be okay too because the string contains only + // ASCII characters, no UTF-8 extended characters. + wsChannel->sendTXT(s); + } + } + + void WSChannels::handleEvent(WebSocketsServer* server, uint8_t num, uint8_t type, uint8_t* payload, size_t length) { + switch (type) { + case WStype_DISCONNECTED: + log_debug("WebSocket disconnect " << num); + WSChannels::removeChannel(num); + break; + case WStype_CONNECTED: { + WSChannel* wsChannel = new WSChannel(server, num); + if (!wsChannel) { + log_error("Creating WebSocket channel failed"); + } else { + std::string uri((char*)payload, length); + + IPAddress ip = server->remoteIP(num); + log_debug("WebSocket " << num << " from " << ip << " uri " << uri); + + _lastWSChannel = wsChannel; + allChannels.registration(wsChannel); + _wsChannels[num] = wsChannel; + + if (uri == "/") { + std::string s("CURRENT_ID:"); + s += std::to_string(num); + // send message to client + _webWsChannels.push_front(wsChannel); + wsChannel->sendTXT(s); + s = "ACTIVE_ID:"; + s += std::to_string(wsChannel->id()); + wsChannel->sendTXT(s); + } + } + } break; + case WStype_TEXT: + case WStype_BIN: + try { + _wsChannels.at(num)->push(payload, length); + } catch (std::out_of_range& oor) {} + break; + default: + break; + } + } } #endif diff --git a/FluidNC/src/WebUI/WSChannel.h b/FluidNC/src/WebUI/WSChannel.h index 4ffccfc98..27d927f5c 100644 --- a/FluidNC/src/WebUI/WSChannel.h +++ b/FluidNC/src/WebUI/WSChannel.h @@ -7,6 +7,8 @@ #include #include +#include +#include class WebSocketsServer; @@ -27,17 +29,13 @@ namespace WebUI { namespace WebUI { class WSChannel : public Channel { - static const int TXBUFFERSIZE = 1200; - static const int RXBUFFERSIZE = 256; - static const int FLUSHTIMEOUT = 500; - public: WSChannel(WebSocketsServer* server, uint8_t clientNum); size_t write(uint8_t c); size_t write(const uint8_t* buffer, size_t size); - size_t sendTXT(std::string& s); + bool sendTXT(std::string& s); inline size_t write(const char* s) { return write((uint8_t*)s, ::strlen(s)); } inline size_t write(unsigned long n) { return write((uint8_t)n); } @@ -45,44 +43,55 @@ namespace WebUI { inline size_t write(unsigned int n) { return write((uint8_t)n); } inline size_t write(int n) { return write((uint8_t)n); } - // void begin(long speed); - // void end(); - void handle(); - bool push(const uint8_t* data, size_t length); - bool push(std::string& s); - void pushRT(char ch); + bool push(const std::string& s); - void flush(void); + void flush(void) override {} int id() { return _clientNum; } - int rx_buffer_available() override { return RXBUFFERSIZE - available(); } + int rx_buffer_available() override { return std::max(0, 256 - int(_queue.size())); } operator bool() const; ~WSChannel(); int read() override; - int available() override { return _rtchar == -1 ? 0 : 1; } + int available() override { return _queue.size() + (_rtchar > -1); } + + void autoReport() override; private: - uint32_t _lastflush; + bool _dead = false; + WebSocketsServer* _server; uint8_t _clientNum; - uint8_t _TXbuffer[TXBUFFERSIZE]; - uint16_t _TXbufferSize; - - uint8_t _RXbuffer[RXBUFFERSIZE]; - uint16_t _RXbufferSize; - uint16_t _RXbufferpos; + std::string _output_line; // Instead of queueing realtime characters, we put them here // so they can be processed immediately during operations like // homing where GCode handling is blocked. int _rtchar = -1; }; + + class WSChannels { + private: + static std::map _wsChannels; + static std::list _webWsChannels; + + static WSChannel* _lastWSChannel; + static WSChannel* getWSChannel(int pageid); + + public: + static void removeChannel(WSChannel* channel); + static void removeChannel(uint8_t num); + + static bool runGCode(int pageid, std::string& cmd); + static bool sendError(int pageid, std::string error); + static void sendPing(); + static void handleEvent(WebSocketsServer* server, uint8_t num, uint8_t type, uint8_t* payload, size_t length); + }; } #endif diff --git a/FluidNC/src/WebUI/WebServer.cpp b/FluidNC/src/WebUI/WebServer.cpp index 6dbca60bd..75737c997 100644 --- a/FluidNC/src/WebUI/WebServer.cpp +++ b/FluidNC/src/WebUI/WebServer.cpp @@ -25,13 +25,15 @@ # include # include "WebSettings.h" +# include "WSChannel.h" + # include "WebClient.h" # include "src/Protocol.h" // protocol_send_event # include "src/FluidPath.h" # include "src/WebUI/JSONEncoder.h" -# include "Driver/localfs.h" +# include "src/HashFS.h" # include namespace WebUI { @@ -45,7 +47,6 @@ namespace WebUI { # include "NoFile.h" namespace WebUI { - // Error codes for upload const int ESP_ERROR_AUTHENTICATION = 1; const int ESP_ERROR_FILE_CREATION = 2; @@ -57,10 +58,7 @@ namespace WebUI { static const char LOCATION_HEADER[] = "Location"; - static std::map wsChannels; - static std::list webWsChannels; - - Web_Server webServer; + Web_Server webServer __attribute__((init_priority(108))); bool Web_Server::_setupdone = false; uint16_t Web_Server::_port = 0; @@ -91,27 +89,6 @@ namespace WebUI { } Web_Server::~Web_Server() { end(); } - WSChannel* Web_Server::lastWSChannel = nullptr; - WSChannel* Web_Server::getWSChannel() { - WSChannel* wsChannel = nullptr; - if (_webserver->hasArg("PAGEID")) { - int wsId = _webserver->arg("PAGEID").toInt(); - wsChannel = wsChannels.at(wsId); - } else { - // If there is no PAGEID URL argument, it is an old version of WebUI - // that does not supply PAGEID in all cases. In that case, we use - // the most recently used websocket if it is still in the list. - for (auto it = wsChannels.begin(); it != wsChannels.end(); ++it) { - if (it->second == lastWSChannel) { - wsChannel = lastWSChannel; - break; - } - } - } - lastWSChannel = wsChannel; - return wsChannel; - } - bool Web_Server::begin() { bool no_error = true; _setupdone = false; @@ -130,6 +107,12 @@ namespace WebUI { //ask server to track these headers _webserver->collectHeaders(headerkeys, headerkeyssize); # endif + + //here the list of headers to be recorded + const char* headerkeys[] = { "If-None-Match" }; + size_t headerkeyssize = sizeof(headerkeys) / sizeof(char*); + _webserver->collectHeaders(headerkeys, headerkeyssize); + _socket_server = new WebSocketsServer(_port + 1); _socket_server->begin(); _socket_server->onEvent(handle_Websocket_Event); @@ -176,7 +159,7 @@ namespace WebUI { } //SSDP service presentation - if (WiFi.getMode() == WIFI_STA) { + if (WiFi.getMode() == WIFI_STA && WebUI::wifi_sta_ssdp->get()) { _webserver->on("/description.xml", HTTP_GET, handle_SSDP); //Add specific for SSDP SSDP.setSchemaURL("description.xml"); @@ -202,10 +185,12 @@ namespace WebUI { _webserver->begin(); //add mDNS - if (WiFi.getMode() == WIFI_STA) { + if (WiFi.getMode() == WIFI_STA && WebUI::wifi_sta_ssdp->get()) { MDNS.addService("http", "tcp", _port); } + HashFS::hash_all(); + _setupdone = true; return no_error; } @@ -240,6 +225,27 @@ namespace WebUI { // Send a file, either the specified path or path.gz bool Web_Server::myStreamFile(const char* path, bool download) { + std::error_code ec; + FluidPath fpath { path, localfsName, ec }; + if (ec) { + return false; + } + + std::string hash; + // Check for brower cache match + + hash = HashFS::hash(fpath); + if (!hash.length()) { + std::filesystem::path gzpath(fpath); + gzpath += ".gz"; + hash = HashFS::hash(gzpath); + } + + if (hash.length() && std::string(_webserver->header("If-None-Match").c_str()) == hash) { + log_debug(path << " is cached"); + _webserver->send(304); + return true; + } // If you load or reload WebUI while a program is running, there is a high // risk of stalling the motion because serving a file from // the local FLASH filesystem takes away a lot of CPU cycles. If we get @@ -258,16 +264,21 @@ namespace WebUI { file = new FileStream(path, "r", ""); } catch (const Error err) { try { - std::string spath(path); - file = new FileStream(spath + ".gz", "r", ""); + std::filesystem::path gzpath(fpath); + gzpath += ".gz"; + file = new FileStream(gzpath, "r", ""); isGzip = true; - } catch (const Error err) { return false; } + } catch (const Error err) { + log_debug(path << " not found"); + return false; + } } if (download) { _webserver->sendHeader("Content-Disposition", "attachment"); } - - log_debug("path " << path << " CT " << getContentType(path)); + if (hash.length()) { + _webserver->sendHeader("ETag", hash.c_str()); + } _webserver->setContentLength(file->size()); if (isGzip) { _webserver->sendHeader("Content-Encoding", "gzip"); @@ -283,7 +294,7 @@ namespace WebUI { delete file; return true; } - void Web_Server::sendWithOurAddress(const char* content) { + void Web_Server::sendWithOurAddress(const char* content, int code) { auto ip = WiFi.getMode() == WIFI_STA ? WiFi.localIP() : WiFi.softAPIP(); std::string ipstr = IP_string(ip); if (_port != 80) { @@ -294,7 +305,7 @@ namespace WebUI { std::string scontent(content); replace_string_in_place(scontent, "$WEB_ADDRESS$", ipstr); replace_string_in_place(scontent, "$QUERY$", _webserver->uri().c_str()); - _webserver->send(200, "text/html", scontent.c_str()); + _webserver->send(code, "text/html", scontent.c_str()); } // Captive Portal Page for use in AP mode @@ -305,7 +316,7 @@ namespace WebUI { "interval=setInterval(function(){\ni=i+1; \nvar x = document.getElementById(\"prg\"); \nx.value=i; \nif (i>5) " "\n{\nclearInterval(interval);\nwindow.location.href='/';\n}\n},1000);\n\n\n\n\n\n"; - void Web_Server::sendCaptivePortal() { sendWithOurAddress(PAGE_CAPTIVE); } + void Web_Server::sendCaptivePortal() { sendWithOurAddress(PAGE_CAPTIVE, 200); } //Default 404 page that is sent when a request cannot be satisfied const char PAGE_404[] = @@ -315,11 +326,12 @@ namespace WebUI { "interval=setInterval(function(){\ni=i+1; \nvar x = document.getElementById(\"prg\"); \nx.value=i; \nif (i>5) " "\n{\nclearInterval(interval);\nwindow.location.href='/';\n}\n},1000);\n\n\n\n\n\n"; - void Web_Server::send404Page() { sendWithOurAddress(PAGE_404); } + void Web_Server::send404Page() { sendWithOurAddress(PAGE_404, 404); } void Web_Server::handle_root() { + log_info("WebUI: Request from " << _webserver->client().remoteIP()); if (!(_webserver->hasArg("forcefallback") && _webserver->arg("forcefallback") == "yes")) { - if (myStreamFile("/index.html")) { + if (myStreamFile("index.html")) { return; } } @@ -358,7 +370,7 @@ namespace WebUI { // This lets the user customize the not-found page by // putting a "404.htm" file on the local filesystem - if (myStreamFile("/404.htm")) { + if (myStreamFile("404.htm")) { return; } @@ -406,6 +418,14 @@ namespace WebUI { _webserver->send(200, "text/xml", sschema); } + // WebUI sends a PAGEID arg to identify the websocket it is using + int Web_Server::getPageid() { + if (_webserver->hasArg("PAGEID")) { + return _webserver->arg("PAGEID").toInt(); + } + return -1; + } + void Web_Server::_handle_web_command(bool silent) { AuthenticationLevel auth_level = is_authenticated(); std::string cmd; @@ -419,32 +439,34 @@ namespace WebUI { } //if it is internal command [ESPXXX] // cmd.trim(); - int ESPpos = cmd.find("[ESP"); - if (ESPpos != std::string::npos) { + auto isCommand = cmd.length() && cmd[0] == '$'; + if (!isCommand) { + isCommand = cmd.find("[ESP") != std::string::npos; + } + if (isCommand) { char line[256]; strncpy(line, cmd.c_str(), 255); webClient.attachWS(_webserver, silent); - Error err = settings_execute_line(line, webClient, auth_level); - std::string answer; - if (err == Error::Ok) { - answer = "ok\n"; - } else { - const char* msg = errorString(err); - answer = "Error: "; + Error err = settings_execute_line(line, webClient, auth_level); + if (err != Error::Ok) { + std::string answer = "Error: "; + const char* msg = errorString(err); if (msg) { answer += msg; } else { answer += std::to_string(static_cast(err)); } answer += "\n"; - } - - // Give the output task a chance to dequeue and forward a message - // to webClient, if there is one. - vTaskDelay(10); - - if (!webClient.anyOutput()) { - _webserver->send(err != Error::Ok ? 500 : 200, "text/plain", answer.c_str()); + _webserver->send(500, "text/plain", answer.c_str()); + } else { + // Give the output task a chance to dequeue and forward a message + // to webClient, if there is one. + for (int i = 0; i < 100 && !webClient.anyOutput(); i++) { + vTaskDelay(10); + } + if (!webClient.anyOutput()) { + _webserver->send(500, "text/plain", "No response"); + } } webClient.detachWS(); } else { //execute GCODE @@ -452,31 +474,7 @@ namespace WebUI { _webserver->send(401, "text/plain", "Authentication failed\n"); return; } - bool hasError = false; - try { - WSChannel* wsChannel = getWSChannel(); - if (wsChannel) { - // It is very tempting to let Serial_2_Socket.push() handle the realtime - // character sequences so we don't have to do it here. That does not work - // because we need to know whether to add a newline. We should not add one - // on a realtime sequence, but we must add one (if not already present) - // on a text command. - if (cmd.length() == 3 && cmd[0] == 0xc2 && is_realtime_command(cmd[1]) && cmd[2] == '\0') { - // Handles old WebUIs that send a null after high-bit-set realtime chars - wsChannel->pushRT(cmd[1]); - } else if (cmd.length() == 2 && cmd[0] == 0xc2 && is_realtime_command(cmd[1])) { - // Handles old WebUIs that send a null after high-bit-set realtime chars - wsChannel->pushRT(cmd[1]); - } else if (cmd.length() == 1 && is_realtime_command(cmd[0])) { - wsChannel->pushRT(cmd[0]); - } else { - if (cmd.length() && cmd[cmd.length() - 1] != '\n') { - cmd += '\n'; - } - hasError = !wsChannel->push(cmd); - } - } - } catch (std::out_of_range& oor) { hasError = true; } + bool hasError = WSChannels::runGCode(getPageid(), cmd); _webserver->send(200, "text/plain", hasError ? "Error" : ""); } @@ -671,12 +669,8 @@ namespace WebUI { s += std::to_string(code) + ":"; s += st; - try { - WSChannel* wsChannel = getWSChannel(); - if (wsChannel) { - wsChannel->sendTXT(s); - } - } catch (std::out_of_range& oor) {} + WSChannels::sendError(getPageid(), st); + if (web_error != 0 && _webserver && _webserver->client().available() > 0) { _webserver->send(web_error, "text/xml", st); } @@ -925,26 +919,47 @@ namespace WebUI { std::string action(_webserver->arg("action").c_str()); std::string filename = std::string(_webserver->arg("filename").c_str()); if (action == "delete") { - if (stdfs::remove(fpath / filename.c_str(), ec)) { + if (stdfs::remove(fpath / filename, ec)) { sstatus = filename + " deleted"; + HashFS::delete_file(fpath / filename); } else { sstatus = "Cannot delete "; sstatus += filename + " " + ec.message(); } } else if (action == "deletedir") { - if (stdfs::remove_all(fpath / filename.c_str(), ec)) { + stdfs::path dirpath { fpath / filename }; + log_debug("Deleting directory " << dirpath); + int count = stdfs::remove_all(dirpath, ec); + if (count > 0) { sstatus = filename + " deleted"; + HashFS::report_change(); } else { + log_debug("remove_all returned " << count); sstatus = "Cannot delete "; sstatus += filename + " " + ec.message(); } } else if (action == "createdir") { if (stdfs::create_directory(fpath / filename, ec)) { sstatus = filename + " created"; + HashFS::report_change(); } else { sstatus = "Cannot create "; sstatus += filename + " " + ec.message(); } + } else if (action == "rename") { + if (!_webserver->hasArg("newname")) { + sstatus = "Missing new filename"; + } else { + std::string newname = std::string(_webserver->arg("newname").c_str()); + std::filesystem::rename(fpath / filename, fpath / newname, ec); + if (ec) { + sstatus = "Cannot rename "; + sstatus += filename + " " + ec.message(); + } else { + sstatus = filename + " renamed to " + newname; + HashFS::rename_file(fpath / filename, fpath / newname); + } + } } } @@ -1053,15 +1068,20 @@ namespace WebUI { // delete _uploadFile; // _uploadFile = nullptr; - auto fpath = _uploadFile->fpath(); + std::string pathname = _uploadFile->fpath(); delete _uploadFile; _uploadFile = nullptr; + log_debug("pathname " << pathname); + + FluidPath filepath { pathname, "" }; + + HashFS::rehash_file(filepath); // Check size if (filesize) { uint32_t actual_size; try { - actual_size = stdfs::file_size(fpath); + actual_size = stdfs::file_size(filepath); } catch (const Error err) { actual_size = 0; } if (filesize != actual_size) { @@ -1086,8 +1106,10 @@ namespace WebUI { _upload_status = UploadStatus::FAILED; log_info("Upload cancelled"); if (_uploadFile) { + std::filesystem::path filepath = _uploadFile->fpath(); delete _uploadFile; _uploadFile = nullptr; + HashFS::rehash_file(filepath); } } void Web_Server::uploadCheck() { @@ -1095,10 +1117,11 @@ namespace WebUI { if (_upload_status == UploadStatus::FAILED) { cancelUpload(); if (_uploadFile) { - auto fpath = _uploadFile->fpath(); + std::filesystem::path filepath = _uploadFile->fpath(); delete _uploadFile; _uploadFile = nullptr; - stdfs::remove(fpath, error_code); + stdfs::remove(filepath, error_code); + HashFS::rehash_file(filepath); } } } @@ -1115,63 +1138,13 @@ namespace WebUI { _socket_server->loop(); } if ((millis() - start_time) > 10000 && _socket_server) { - for (WSChannel* wsChannel : webWsChannels) { - std::string s("PING:"); - s += wsChannel->id(); - wsChannel->sendTXT(s); - } - + WSChannels::sendPing(); start_time = millis(); } } void Web_Server::handle_Websocket_Event(uint8_t num, uint8_t type, uint8_t* payload, size_t length) { - char data[length + 1]; - memcpy(data, (char*)payload, length); - data[length] = '\0'; - - switch (type) { - case WStype_DISCONNECTED: - log_debug("WebSocket disconnect " << num); - try { - WSChannel* wsChannel = wsChannels.at(num); - webWsChannels.remove(wsChannel); - allChannels.kill(wsChannel); - wsChannels.erase(num); - } catch (std::out_of_range& oor) {} - break; - case WStype_CONNECTED: { - IPAddress ip = _socket_server->remoteIP(num); - WSChannel* wsChannel = new WSChannel(_socket_server, num); - if (!wsChannel) { - log_error("Creating WebSocket channel failed"); - } else { - lastWSChannel = wsChannel; - log_debug("WebSocket " << num << " from " << ip << " uri " << data); - allChannels.registration(wsChannel); - wsChannels[num] = wsChannel; - - if (strcmp(data, "/") == 0) { - std::string s("CURRENT_ID:"); - s += std::to_string(num); - // send message to client - webWsChannels.push_front(wsChannel); - wsChannel->sendTXT(s); - s = "ACTIVE_ID:"; - s += std::to_string(wsChannel->id()); - wsChannel->sendTXT(s); - } - } - } break; - case WStype_TEXT: - case WStype_BIN: - try { - wsChannels.at(num)->push(payload, length); - } catch (std::out_of_range& oor) {} - break; - default: - break; - } + WSChannels::handleEvent(_socket_server, num, type, payload, length); } //Convert file extension to content type diff --git a/FluidNC/src/WebUI/WebServer.h b/FluidNC/src/WebUI/WebServer.h index 9434b8d60..ee20adbe2 100644 --- a/FluidNC/src/WebUI/WebServer.h +++ b/FluidNC/src/WebUI/WebServer.h @@ -11,7 +11,6 @@ # include "../Settings.h" # include "Authentication.h" // AuthenticationLevel # include "Commands.h" -# include "WSChannel.h" class WebSocketsServer; class WebServer; @@ -111,12 +110,11 @@ namespace WebUI { static void sendAuthFailed(); static void sendStatus(int code, const char* str); - static void sendWithOurAddress(const char* s); + static void sendWithOurAddress(const char* s, int code); static void sendCaptivePortal(); static void send404Page(); - static WSChannel* lastWSChannel; - static WSChannel* getWSChannel(); + static int getPageid(); }; extern Web_Server webServer; diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 45f9ab4d8..aefc8486a 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -17,11 +17,11 @@ #include "../Report.h" // git_info #include "../InputFile.h" // InputFile -#include "Driver/localfs.h" // localfs_format - #include "Commands.h" // COMMANDS::restart_MCU(); #include "WifiConfig.h" +#include "src/HashFS.h" + #include #include #include @@ -255,7 +255,7 @@ namespace WebUI { // NVS settings j.setCategory("nvs"); - for (Setting* js = Setting::List; js; js = js->next()) { + for (Setting* js : Setting::List) { js->addWebui(&j); } @@ -312,6 +312,17 @@ namespace WebUI { return Error::Ok; } + static bool split(char* input, char** next, char delim) { + char* pos = strchr(input, delim); + if (pos) { + *pos = '\0'; + *next = pos + 1; + return true; + } + *next = input + strlen(input); // End of string + return false; + } + static Error showSDFile(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP221 return showFile("sd", parameter, auth_level, out); } @@ -319,6 +330,73 @@ namespace WebUI { return showFile("", parameter, auth_level, out); } + static Error showFileSome(const char* fs, char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP221 + if (notIdleOrAlarm()) { + return Error::IdleError; + } + if (!parameter || !*parameter) { + log_error_to(out, "Missing argument"); + return Error::InvalidValue; + } + int firstline = 0; + int lastline = 0; + char* filename; + split(parameter, &filename, ','); + if (*filename == '\0') { + log_error_to(out, "Missing filename"); + return Error::InvalidValue; + } + + // Parameter is the list of lines to display + // N means the first N lines + // N:M means lines N through M inclusive + if (!*parameter) { + log_error_to(out, "Missing line count"); + return Error::InvalidValue; + } + char* second; + split(parameter, &second, ':'); + if (*second) { + firstline = atoi(parameter); + lastline = atoi(second); + } else { + firstline = 0; + lastline = atoi(parameter); + } + InputFile* theFile; + Error err; + if ((err = openFile(fs, filename, auth_level, out, theFile)) != Error::Ok) { + log_error_to(out, "Cannot open file " << filename); + return err; + } + char fileLine[255]; + Error res; + for (int linenum = 0; (res = theFile->readLine(fileLine, 255)) == Error::Ok; ++linenum) { + if (linenum >= lastline) { + break; + } + if (linenum >= firstline) { + // We cannot use the 2-argument form of log_to() here because + // fileLine can be overwritten by readLine before the output + // task has a chance to forward the line to the output channel. + // The 3-argument form works because it copies the line to a + // temporary string. + log_to(out, "", fileLine); + } + } + if (res != Error::Eof && res != Error::Ok) { + log_to(out, errorString(res)); + } + delete theFile; + return Error::Ok; + } + + static Error showSDSome(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP221 + return showFileSome("sd", parameter, auth_level, out); + } + static Error showLocalSome(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP701 + return showFileSome("", parameter, auth_level, out); + } static Error runFile(const char* fs, char* parameter, AuthenticationLevel auth_level, Channel& out) { Error err; if (sys.state == State::Alarm || sys.state == State::ConfigAlarm) { @@ -351,6 +429,11 @@ namespace WebUI { static Error deleteObject(const char* fs, char* name, Channel& out) { std::error_code ec; + if (!name || !*name || (strcmp(name, "/") == 0)) { + // Disallow deleting everything + log_error_to(out, "Will not delete everything"); + return Error::InvalidValue; + } FluidPath fpath { name, fs, ec }; if (ec) { log_to(out, "No SD"); @@ -374,6 +457,7 @@ namespace WebUI { return Error::FsFailedDelFile; } } + HashFS::delete_file(fpath); return Error::Ok; } @@ -433,7 +517,91 @@ namespace WebUI { return listFilesystem(localfsName, parameter, auth_level, out); } + static Error listFilesystemJSON(const char* fs, const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + std::error_code ec; + + FluidPath fpath { value, fs, ec }; + if (ec) { + log_to(out, "No SD card"); + return Error::FsFailedMount; + } + + JSONencoder j(false, &out); + j.begin(); + + auto iter = stdfs::directory_iterator { fpath, ec }; + if (ec) { + log_to(out, "Error: ", ec.message()); + return Error::FsFailedMount; + } + j.begin_array("files"); + for (auto const& dir_entry : iter) { + j.begin_object(); + j.member("name", dir_entry.path().filename()); + j.member("size", dir_entry.is_directory() ? -1 : dir_entry.file_size()); + j.end_object(); + } + j.end_array(); + + auto space = stdfs::space(fpath, ec); + if (ec) { + log_to(out, "Error ", ec.value() << " " << ec.message()); + return Error::FsFailedMount; + } + + auto totalBytes = space.capacity; + auto freeBytes = space.available; + auto usedBytes = totalBytes - freeBytes; + + j.member("path", value); + j.member("total", formatBytes(totalBytes)); + j.member("used", formatBytes(usedBytes + 1)); + + uint32_t percent = totalBytes ? (usedBytes * 100) / totalBytes : 100; + + j.member("occupation", percent); + j.end(); + return Error::Ok; + } + + static Error listSDFilesJSON(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP210 + return listFilesystemJSON(sdName, parameter, auth_level, out); + } + + static Error listLocalFilesJSON(char* parameter, AuthenticationLevel auth_level, Channel& out) { // No ESP command + return listFilesystemJSON(localfsName, parameter, auth_level, out); + } + + static Error renameObject(const char* fs, char* parameter, AuthenticationLevel auth_level, Channel& out) { + if (!parameter || *parameter == '\0') { + return Error::InvalidValue; + } + auto opath = strchr(parameter, '>'); + if (*opath == '\0') { + return Error::InvalidValue; + } + const char* ipath = parameter; + *opath++ = '\0'; + try { + FluidPath inPath { ipath, fs }; + FluidPath outPath { opath, fs }; + std::filesystem::rename(inPath, outPath); + HashFS::rename_file(inPath, outPath, true); + } catch (const Error err) { + log_error_to(out, "Cannot rename " << ipath << " to " << opath); + return Error::FsFailedRenameFile; + } + return Error::Ok; + } + static Error renameSDObject(char* parameter, AuthenticationLevel auth_level, Channel& out) { + return renameObject(sdName, parameter, auth_level, out); + } + static Error renameLocalObject(char* parameter, AuthenticationLevel auth_level, Channel& out) { + return renameObject(localfsName, parameter, auth_level, out); + } + static Error copyFile(const char* ipath, const char* opath, Channel& out) { // No ESP command + std::filesystem::path filepath; try { FileStream outFile { opath, "w" }; FileStream inFile { ipath, "r" }; @@ -442,10 +610,13 @@ namespace WebUI { while ((len = inFile.read(buf, 512)) > 0) { outFile.write(buf, len); } + filepath = outFile.fpath(); } catch (const Error err) { - log_error("Cannot create file " << opath); + log_error_to(out, "Cannot create file " << opath); return Error::FsFailedCreateFile; } + // Rehash after outFile goes out of scope + HashFS::rehash_file(filepath); return Error::Ok; } static Error copyDir(const char* iDir, const char* oDir, Channel& out) { // No ESP command @@ -481,7 +652,7 @@ namespace WebUI { Error err = Error::Ok; for (auto const& dir_entry : iter) { if (dir_entry.is_directory()) { - log_error("Not handling localfs subdirectories"); + log_error_to(out, "Not handling localfs subdirectories"); } else { std::string opath(oDir); opath += "/"; @@ -498,6 +669,13 @@ namespace WebUI { } return err; } + static Error showLocalFSHashes(char* parameter, WebUI::AuthenticationLevel auth_level, Channel& out) { + for (const auto& [name, hash] : HashFS::localFsHashes) { + log_info_to(out, name << ": " << hash); + } + return Error::Ok; + } + static Error backupLocalFS(char* parameter, AuthenticationLevel auth_level, Channel& out) { // No ESP command return copyDir("/localfs", "/sd/localfs", out); } @@ -507,7 +685,7 @@ namespace WebUI { static Error migrateLocalFS(char* parameter, AuthenticationLevel auth_level, Channel& out) { // No ESP command const char* newfs = parameter && *parameter ? parameter : "littlefs"; if (strcmp(newfs, localfsName) == 0) { - log_error("localfs format is already " << newfs); + log_error_to(out, "localfs format is already " << newfs); return Error::InvalidValue; } log_info("Backing up local filesystem contents to SD"); @@ -572,7 +750,7 @@ namespace WebUI { log_to(out, "ESPname FullName Description"); log_to(out, "------- -------- -----------"); ; - for (Setting* setting = Setting::List; setting; setting = setting->next()) { + for (Setting* setting : Setting::List) { if (setting->getType() == WEBSET) { log_to(out, "", @@ -585,7 +763,7 @@ namespace WebUI { log_to(out, "ESPname FullName Values"); log_to(out, "------- -------- ------"); - for (Command* cp = Command::List; cp; cp = cp->next()) { + for (Command* cp : Command::List) { if (cp->getType() == WEBCMD) { LogStream s(out, ""); s << LeftJustify(cp->getGrblName() ? cp->getGrblName() : "", 8) << LeftJustify(cp->getName(), 25 - 8); @@ -637,18 +815,21 @@ namespace WebUI { new WebCommand("path", WEBCMD, WU, "ESP701", "LocalFS/Show", showLocalFile); new WebCommand("path", WEBCMD, WU, "ESP700", "LocalFS/Run", runLocalFile); new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/List", listLocalFiles); -#if 0 new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/ListJSON", listLocalFilesJSON); -#endif new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/Delete", deleteLocalFile); + new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/Rename", renameLocalObject); new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/Backup", backupLocalFS); new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/Restore", restoreLocalFS); new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/Migrate", migrateLocalFS); + new WebCommand(NULL, WEBCMD, WU, NULL, "LocalFS/Hashes", showLocalFSHashes); + new WebCommand("path", WEBCMD, WU, "ESP221", "SD/ShowSome", showSDSome); new WebCommand("path", WEBCMD, WU, "ESP221", "SD/Show", showSDFile); new WebCommand("path", WEBCMD, WU, "ESP220", "SD/Run", runSDFile); new WebCommand("file_or_directory_path", WEBCMD, WU, "ESP215", "SD/Delete", deleteSDObject); + new WebCommand("path", WEBCMD, WU, NULL, "SD/Rename", renameSDObject); new WebCommand(NULL, WEBCMD, WU, "ESP210", "SD/List", listSDFiles); + new WebCommand("path", WEBCMD, WU, NULL, "SD/ListJSON", listSDFilesJSON); new WebCommand(NULL, WEBCMD, WU, "ESP200", "SD/Status", showSDStatus); new WebCommand("ON|OFF", WEBCMD, WA, "ESP115", "Radio/State", setRadioState); diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index dd589533e..df8b26819 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -8,7 +8,7 @@ #include #include -WebUI::WiFiConfig wifi_config; +WebUI::WiFiConfig wifi_config __attribute__((init_priority(109))); #ifdef ENABLE_WIFI # include "../Config.h" @@ -114,6 +114,7 @@ namespace WebUI { IPaddrSetting* wifi_sta_ip; IPaddrSetting* wifi_sta_gateway; IPaddrSetting* wifi_sta_netmask; + EnumSetting* wifi_sta_ssdp; StringSetting* wifi_ap_ssid; StringSetting* wifi_ap_password; @@ -337,9 +338,10 @@ namespace WebUI { MIN_PASSWORD_LENGTH, MAX_PASSWORD_LENGTH, (bool (*)(char*))WiFiConfig::isPasswordValid); - wifi_ap_ssid = new StringSetting( - "AP SSID", WEBSET, WA, "ESP105", "AP/SSID", DEFAULT_AP_SSID, MIN_SSID_LENGTH, MAX_SSID_LENGTH, (bool (*)(char*))WiFiConfig::isSSIDValid); - wifi_ap_country = new EnumSetting("AP regulatory domain", WEBSET, WA, NULL, "AP/Country", WiFiCountry01, &wifiContryOptions, NULL); + wifi_ap_ssid = new StringSetting("AP SSID", WEBSET, WA, "ESP105", "AP/SSID", DEFAULT_AP_SSID, MIN_SSID_LENGTH, MAX_SSID_LENGTH, NULL); + wifi_ap_country = new EnumSetting("AP regulatory domain", WEBSET, WA, NULL, "AP/Country", WiFiCountry01, &wifiContryOptions, NULL); + wifi_sta_ssdp = + new EnumSetting("SSDP and mDNS enable", WEBSET, WA, NULL, "Sta/SSDP/Enable", DEFAULT_STA_SSDP_ENABLED, &onoffOptions, NULL); wifi_sta_netmask = new IPaddrSetting("Station Static Mask", WEBSET, WA, NULL, "Sta/Netmask", DEFAULT_STA_MK, NULL); wifi_sta_gateway = new IPaddrSetting("Station Static Gateway", WEBSET, WA, NULL, "Sta/Gateway", DEFAULT_STA_GW, NULL); wifi_sta_ip = new IPaddrSetting("Station Static IP", WEBSET, WA, NULL, "Sta/IP", DEFAULT_STA_IP, NULL); @@ -356,15 +358,8 @@ namespace WebUI { MIN_PASSWORD_LENGTH, MAX_PASSWORD_LENGTH, (bool (*)(char*))WiFiConfig::isPasswordValid); - wifi_sta_ssid = new StringSetting("Station SSID", - WEBSET, - WA, - "ESP100", - "Sta/SSID", - DEFAULT_STA_SSID, - MIN_SSID_LENGTH, - MAX_SSID_LENGTH, - (bool (*)(char*))WiFiConfig::isSSIDValid); + wifi_sta_ssid = + new StringSetting("Station SSID", WEBSET, WA, "ESP100", "Sta/SSID", DEFAULT_STA_SSID, MIN_SSID_LENGTH, MAX_SSID_LENGTH, NULL); wifi_mode = new EnumSetting("WiFi mode", WEBSET, WA, "ESP116", "WiFi/Mode", WiFiFallback, &wifiModeOptions, NULL); @@ -469,26 +464,6 @@ namespace WebUI { return true; } - /** - * Check if SSID string is valid - */ - - bool WiFiConfig::isSSIDValid(const char* ssid) { - //limited size - //char c; - // length is checked automatically by string setting - //only printable - if (!ssid) { - return true; - } - for (int i = 0; i < strlen(ssid); i++) { - if (!isPrintable(ssid[i])) { - return false; - } - } - return true; - } - /** * Check if password string is valid */ @@ -617,18 +592,33 @@ namespace WebUI { if ((WiFi.getMode() == WIFI_AP) || (WiFi.getMode() == WIFI_AP_STA)) { WiFi.softAPdisconnect(); } + WiFi.enableAP(false); + + // Set the number of receive and transmit buffers that the + // WiFi stack can use. Making these numbers too large + // can eat up a lot of memory at 1.6K per buffer. It + // can be especially bad when there are many dynamic buffers, + // If there are too few Rx buffers, file upload can fail, + // possibly due to IP packet fragments getting lost. The limit + // for what works seems to be 4 static, 4 dynamic. + // allowing external network traffic to use a lot of the heap. + // The bawin parameters are for AMPDU aggregation. + // rx: static dynamic bawin tx: static dynamic bawin cache + WiFi.setBuffers(4, 5, 0, 4, 0, 0, 4); + //SSID const char* SSID = wifi_sta_ssid->get(); if (strlen(SSID) == 0) { log_info("STA SSID is not set"); return false; } + //Hostname needs to be set before mode to take effect + WiFi.setHostname(wifi_hostname->get()); WiFi.mode(WIFI_STA); WiFi.setMinSecurity(static_cast(wifi_sta_min_security->get())); WiFi.setScanMethod(wifi_fast_scan->get() ? WIFI_FAST_SCAN : WIFI_ALL_CHANNEL_SCAN); //Get parameters for STA - WiFi.setHostname(wifi_hostname->get()); //password const char* password = wifi_sta_password->get(); int8_t IP_mode = wifi_sta_mode->get(); @@ -800,7 +790,7 @@ namespace WebUI { bool error = false; // XXX this is probably wrong for YAML land. // We might want this function to go away. - for (Setting* s = Setting::List; s; s = s->next()) { + for (Setting* s : Setting::List) { if (s->getDescription()) { s->setDefault(); } diff --git a/FluidNC/src/WebUI/WifiConfig.h b/FluidNC/src/WebUI/WifiConfig.h index 3fe426eea..8ff92f1db 100644 --- a/FluidNC/src/WebUI/WifiConfig.h +++ b/FluidNC/src/WebUI/WifiConfig.h @@ -56,6 +56,7 @@ namespace WebUI { static const int DEFAULT_STA_MIN_SECURITY = WIFI_AUTH_WPA2_PSK; static const int DEFAULT_STA_IP_MODE = DHCP_MODE; + static const int DEFAULT_STA_SSDP_ENABLED = true; static const char* HIDDEN_PASSWORD = "********"; //boundaries @@ -83,7 +84,6 @@ namespace WebUI { static bool isValidIP(const char* string); static bool isPasswordValid(const char* password); - static bool isSSIDValid(const char* ssid); static bool isHostnameValid(const char* hostname); static std::string Hostname() { return _hostname; } @@ -125,6 +125,7 @@ namespace WebUI { extern IPaddrSetting* wifi_sta_ip; extern IPaddrSetting* wifi_sta_gateway; extern IPaddrSetting* wifi_sta_netmask; + extern EnumSetting* wifi_sta_ssdp; extern StringSetting* wifi_ap_ssid; extern StringSetting* wifi_ap_password; diff --git a/FluidNC/src/WebUI/WifiServices.cpp b/FluidNC/src/WebUI/WifiServices.cpp index d01a002c6..0d322abdd 100644 --- a/FluidNC/src/WebUI/WifiServices.cpp +++ b/FluidNC/src/WebUI/WifiServices.cpp @@ -82,7 +82,7 @@ namespace WebUI { }); ArduinoOTA.begin(); //no need in AP mode - if (WiFi.getMode() == WIFI_STA) { + if (WiFi.getMode() == WIFI_STA && WebUI::wifi_sta_ssdp->get()) { //start mDns const char* h = wifi_hostname->get(); if (!MDNS.begin(h)) { diff --git a/FluidNC/src/string_util.cpp b/FluidNC/src/string_util.cpp new file mode 100644 index 000000000..bb4d6aaa6 --- /dev/null +++ b/FluidNC/src/string_util.cpp @@ -0,0 +1,49 @@ +#include "string_util.h" +#include + +namespace string_util { + char tolower(char c) { + if (c >= 'A' && c <= 'Z') { + return c + ('a' - 'A'); + } + return c; + } + + bool equal_ignore_case(std::string_view a, std::string_view b) { + return std::equal(a.begin(), a.end(), b.begin(), b.end(), [](auto a, auto b) { return tolower(a) == tolower(b); }); + } + + bool starts_with_ignore_case(std::string_view a, std::string_view b) { + return std::equal(a.begin(), a.begin() + b.size(), b.begin(), b.end(), [](auto a, auto b) { return tolower(a) == tolower(b); }); + } + + const std::string_view trim(std::string_view s) { + auto start = s.find_first_not_of(" \t\n\r\f\v"); + if (start == std::string_view::npos) { + return ""; + } + auto end = s.find_last_not_of(" \t\n\r\f\v"); + if (end == std::string_view::npos) { + return s.substr(start); + } + return s.substr(start, end - start + 1); + } + + bool is_int(std::string_view s, int32_t& value) { + char* end; + value = std::strtol(s.cbegin(), &end, 10); + return end == s.cend(); + } + + bool is_uint(std::string_view s, uint32_t& value) { + char* end; + value = std::strtoul(s.cbegin(), &end, 10); + return end == s.cend(); + } + + bool is_float(std::string_view s, float& value) { + char* end; + value = std::strtof(s.cbegin(), &end); + return end == s.cend(); + } +} diff --git a/FluidNC/src/string_util.h b/FluidNC/src/string_util.h new file mode 100644 index 000000000..e363344c3 --- /dev/null +++ b/FluidNC/src/string_util.h @@ -0,0 +1,14 @@ +#pragma once + +#include + +namespace string_util { + char tolower(char c); + bool equal_ignore_case(std::string_view a, std::string_view b); + bool starts_with_ignore_case(std::string_view a, std::string_view b); + const std::string_view trim(std::string_view s); + + bool is_int(std::string_view s, int32_t& value); + bool is_uint(std::string_view s, uint32_t& value); + bool is_float(std::string_view s, float& value); +} diff --git a/FluidNC/stdfs/std-ops.cpp b/FluidNC/stdfs/std-ops.cpp index c5eea3959..746a6b433 100644 --- a/FluidNC/stdfs/std-ops.cpp +++ b/FluidNC/stdfs/std-ops.cpp @@ -907,8 +907,10 @@ bool fs::remove(const path& p) { return result; } bool fs::remove(const path& p, error_code& ec) noexcept { - if (exists(symlink_status(p, ec))) { - if (::remove(p.c_str()) == 0) { + auto fs = symlink_status(p, ec); + if (exists(fs)) { + int res = fs.type() == file_type::directory ? ::rmdir(p.c_str()) : ::remove(p.c_str()); + if (res == 0) { ec.clear(); return true; } else diff --git a/FluidNC/test/Pins/ErrorPinTest.cpp b/FluidNC/test/Pins/ErrorPinTest.cpp index d673296f6..3cf7320fe 100644 --- a/FluidNC/test/Pins/ErrorPinTest.cpp +++ b/FluidNC/test/Pins/ErrorPinTest.cpp @@ -16,9 +16,6 @@ namespace Pins { AssertThrow(errorPin.write(true)); AssertThrow(errorPin.read()); - AssertThrow(errorPin.attachInterrupt([](void* arg) {}, EITHER_EDGE)); - AssertThrow(errorPin.detachInterrupt()); - Assert(errorPin.capabilities() == Pin::Capabilities::Error, "Incorrect caps"); } } diff --git a/FluidNC/test/Pins/GPIO.cpp b/FluidNC/test/Pins/GPIO.cpp index c17acdde3..6fb68b558 100644 --- a/FluidNC/test/Pins/GPIO.cpp +++ b/FluidNC/test/Pins/GPIO.cpp @@ -114,16 +114,6 @@ namespace Pins { gpio16.setAttr(Pin::Attr::Input | Pin::Attr::ISR); gpio17.setAttr(Pin::Attr::Output); - int hitCount = 0; - int expected = 0; - gpio16.attachInterrupt( - [](void* arg) { - int* hc = static_cast(arg); - ++(*hc); - }, - mode, - &hitCount); - // Two ways to set I/O: // 1. using on/off // 2. external source (e.g. set softwareio pin value) @@ -299,10 +289,6 @@ namespace Pins { gpio16.setAttr(Pin::Attr::Input | Pin::Attr::ISR); gpio17.setAttr(Pin::Attr::Output); - hitCount = 0; - int expected = 0; - gpio16.attachInterrupt(this, mode); - // Two ways to set I/O: // 1. using on/off // 2. external source (e.g. set softwareio pin value) diff --git a/FluidNC/test/Pins/Undefined.cpp b/FluidNC/test/Pins/Undefined.cpp index 8d68c27a5..d2e356c28 100644 --- a/FluidNC/test/Pins/Undefined.cpp +++ b/FluidNC/test/Pins/Undefined.cpp @@ -21,9 +21,6 @@ namespace Pins { Assert(0 == result, "Result value incorrect"); } - AssertThrow(unassigned.attachInterrupt([](void* arg) {}, EITHER_EDGE)); - AssertThrow(unassigned.detachInterrupt()); - Assert(unassigned.capabilities().has(Pin::Capabilities::Void)); auto name = unassigned.name(); Assert(unassigned.name().equals("NO_PIN")); diff --git a/FluidNC/tests/PinOptionsParserTest.cpp b/FluidNC/tests/PinOptionsParserTest.cpp new file mode 100644 index 000000000..696c864b5 --- /dev/null +++ b/FluidNC/tests/PinOptionsParserTest.cpp @@ -0,0 +1,193 @@ +// Copyright (c) 2023 - Dylan Knutson +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#include "gtest/gtest.h" +#include "src/Pins/PinOptionsParser.h" + +using PinOptionsParser = Pins::PinOptionsParser; +static void test_for_loop(PinOptionsParser& parser); +static void test_for_loop_only_first(PinOptionsParser& parser); + +TEST(PinOptionsParser, WithEmptyString) { + char nullDescr[1] = { '\0' }; + PinOptionsParser parser(nullDescr, nullDescr); + + { + auto opt = parser.begin(); + auto endopt = parser.end(); + ASSERT_EQ(opt, endopt) << "Expected empty enumerator"; + } + + // Typical use is a for loop. Let's test the two ways to use it: + for (auto it : parser) { + FAIL() << "Didn't expect to get here"; + } + + for (auto it = parser.begin(); it != parser.end(); ++it) { + FAIL() << "Didn't expect to get here"; + } +} + +TEST(PinOptionsParser, SingleArg) { + const char* input = "first"; + char tmp[20]; + int n = snprintf(tmp, 20, "%s", input); + + PinOptionsParser parser(tmp, tmp + n); + + { + auto opt = parser.begin(); + auto endopt = parser.end(); + ASSERT_NE(opt, endopt) << "Expected an argument"; + ASSERT_TRUE(opt->is("first")) << "Expected 'first'"; + ++opt; + ASSERT_EQ(opt, endopt) << "Expected one argument"; + } + + test_for_loop_only_first(parser); +} + +TEST(PinOptionsParser, SingleArgWithWS) { + const char* input = " first"; + char tmp[20]; + int n = snprintf(tmp, 20, "%s", input); + + PinOptionsParser parser(tmp, tmp + n); + + { + auto opt = parser.begin(); + auto endopt = parser.end(); + ASSERT_NE(opt, endopt) << "Expected an argument"; + ASSERT_TRUE(opt->is("first")) << "Expected 'first'"; + ++opt; + ASSERT_EQ(opt, endopt) << "Expected one argument"; + } + + test_for_loop_only_first(parser); +} + +TEST(PinOptionsParser, SingleArgWithWS2) { + const char* input = " first "; + char tmp[20]; + int n = snprintf(tmp, 20, "%s", input); + + PinOptionsParser parser(tmp, tmp + n); + + { + auto opt = parser.begin(); + auto endopt = parser.end(); + ASSERT_NE(opt, endopt) << "Expected an argument"; + ASSERT_TRUE(opt->is("first")) << "Expected 'first'"; + + ++opt; + ASSERT_EQ(opt, endopt) << "Expected one argument"; + } + + test_for_loop_only_first(parser); +} + +TEST(PinOptionsParser, TwoArg1) { + const char* input = "first;second"; + char tmp[20]; + int n = snprintf(tmp, 20, "%s", input); + + PinOptionsParser parser(tmp, tmp + n); + + { + auto opt = parser.begin(); + auto endopt = parser.end(); + ASSERT_NE(opt, endopt) << "Expected an argument"; + ASSERT_TRUE(opt->is("first")) << "Expected 'first'"; + + ++opt; + ASSERT_NE(opt, endopt) << "Expected second argument"; + ASSERT_TRUE(opt->is("second")) << "Expected 'second'"; + + ++opt; + ASSERT_EQ(opt, endopt) << "Expected one argument"; + } + + test_for_loop(parser); +} + +TEST(PinOptionsParser, TwoArg2) { + const char* input = "first:second"; + char tmp[20]; + int n = snprintf(tmp, 20, "%s", input); + + PinOptionsParser parser(tmp, tmp + n); + + { + auto opt = parser.begin(); + auto endopt = parser.end(); + ASSERT_NE(opt, endopt) << "Expected an argument"; + ASSERT_TRUE(opt->is("first")) << "Expected 'first'"; + + ++opt; + ASSERT_NE(opt, endopt) << "Expected second argument"; + ASSERT_TRUE(opt->is("second")) << "Expected 'second'"; + + ++opt; + ASSERT_EQ(opt, endopt) << "Expected one argument"; + } + + test_for_loop(parser); +} + +TEST(PinOptionsParser, TwoArgWithValues) { + const char* input = "first=12;second=13"; + char tmp[20]; + int n = snprintf(tmp, 20, "%s", input); + + PinOptionsParser parser(tmp, tmp + n); + + { + auto opt = parser.begin(); + auto endopt = parser.end(); + ASSERT_NE(opt, endopt) << "Expected an argument"; + ASSERT_TRUE(opt->is("first")) << "Expected 'first'"; + ASSERT_EQ(strcmp("12", opt->value()), 0); + ASSERT_EQ(12, opt->iValue()); + ASSERT_EQ(12, opt->dValue()); + + ++opt; + ASSERT_NE(opt, endopt) << "Expected second argument"; + ASSERT_TRUE(opt->is("second")) << "Expected 'second'"; + ASSERT_EQ(strcmp("13", opt->value()), 0); + ASSERT_EQ(13, opt->iValue()); + ASSERT_EQ(13, opt->dValue()); + + ++opt; + ASSERT_EQ(opt, endopt) << "Expected one argument"; + } + + test_for_loop(parser); +} + +static void test_for_loop(PinOptionsParser& parser) { + // Typical use is a for loop. Let's test the two ways to use it: + int ctr = 0; + for (auto it : parser) { + if (ctr == 0) { + ASSERT_TRUE(it.is("first")) << "Expected 'first'"; + } else if (ctr == 1) { + ASSERT_TRUE(it.is("second")) << "Expected 'second'"; + } else { + FAIL() << "Didn't expect to get here"; + } + ++ctr; + } +} + +static void test_for_loop_only_first(PinOptionsParser& parser) { + // Typical use is a for loop. Let's test the two ways to use it: + int ctr = 0; + for (auto it : parser) { + if (ctr == 0) { + ASSERT_TRUE(it.is("first")) << "Expected 'first'"; + } else { + FAIL() << "Didn't expect to get here"; + } + ++ctr; + } +} diff --git a/FluidNC/tests/test_main.cpp b/FluidNC/tests/test_main.cpp new file mode 100644 index 000000000..924185ef7 --- /dev/null +++ b/FluidNC/tests/test_main.cpp @@ -0,0 +1,12 @@ +#include "gtest/gtest.h" + +int main(int argc, char** argv) { + ::testing::InitGoogleTest(&argc, argv); + // if you plan to use GMock, replace the line above with + // ::testing::InitGoogleMock(&argc, argv); + + if (RUN_ALL_TESTS()) {} + + // Always return zero-code and allow PlatformIO to parse results + return 0; +} diff --git a/ISSUE_TEMPLATE/problem.yml b/ISSUE_TEMPLATE/problem.yml index 528b90ef5..a1cbb3517 100644 --- a/ISSUE_TEMPLATE/problem.yml +++ b/ISSUE_TEMPLATE/problem.yml @@ -7,7 +7,7 @@ body: - type: markdown attributes: value: | - Please fill in the forms below. The better the information you provide, the better we can help you. + Please read http://wiki.fluidnc.com/en/support/requesting_help, then fill in the forms below. The better the information you provide, the better we can help you. Information that you might think is irrelevant is often the key to solving the problem. - type: textarea id: controller-board diff --git a/build-release.py b/build-release.py index 97dd45959..1bf211723 100644 --- a/build-release.py +++ b/build-release.py @@ -6,6 +6,7 @@ from zipfile import ZipFile, ZipInfo import subprocess, os, sys, shutil import urllib.request +import io, hashlib verbose = '-v' in sys.argv @@ -24,7 +25,7 @@ def buildEnv(pioEnv, verbose=True, extraArgs=None): if verbose: app = subprocess.Popen(cmd, env=environ) else: - app = subprocess.Popen(cmd, env=environ, stdout=subprocess.PIPE, stderr=subprocess.STDOUT, bufsize=1) + app = subprocess.Popen(cmd, env=environ, stdout=subprocess.PIPE, stderr=subprocess.STDOUT) for line in app.stdout: line = line.decode('utf8') if "Took" in line or 'Uploading' in line or ("error" in line.lower() and "Compiling" not in line): @@ -41,7 +42,7 @@ def buildFs(pioEnv, verbose=verbose, extraArgs=None): if verbose: app = subprocess.Popen(cmd, env=environ) else: - app = subprocess.Popen(cmd, env=environ, stdout=subprocess.PIPE, stderr=subprocess.STDOUT, bufsize=1) + app = subprocess.Popen(cmd, env=environ, stdout=subprocess.PIPE, stderr=subprocess.STDOUT) for line in app.stdout: line = line.decode('utf8') if "Took" in line or 'Uploading' in line or ("error" in line.lower() and "Compiling" not in line): @@ -71,17 +72,165 @@ def copyToZip(zipObj, platform, fileName, destPath, mode=0o100755): if not os.path.exists(relPath): os.makedirs(relPath) +manifestRelPath = os.path.join(relPath, 'current') +if os.path.exists(manifestRelPath): + shutil.rmtree(manifestRelPath) + +os.makedirs(manifestRelPath) + +# Copy the web application to the release directory +dataRelPath = os.path.join(manifestRelPath, 'data') +os.makedirs(dataRelPath) +shutil.copy(os.path.join("FluidNC", "data", "index.html.gz"), dataRelPath) + +manifest = { + "name": "FluidNC", + "version": tag, + "source_url": "https://github.com/bdring/FluidNC/tree/" + tag, + "release_url": "https://github.com/bdring/FluidNC/releases/tag/" + tag, + "funding_url": "https://www.paypal.com/donate/?hosted_button_id=8DYLB6ZYYDG7Y", + "images": {}, + "installable": { + "name": "installable", + "description": "Things you can install", + "choice-name": "Processor type", + "choices": [] + }, +} + # We avoid doing this every time, instead checking in a new NoFile.h as necessary # if buildEmbeddedPage() != 0: # sys.exit(1) -if buildFs('wifi', verbose=verbose) != 0: - sys.exit(1) +# if buildFs('wifi', verbose=verbose) != 0: +# sys.exit(1) + +def addImage(name, offset, filename, srcpath, dstpath): + fulldstpath = os.path.join(manifestRelPath,os.path.normpath(dstpath)) + + os.makedirs(fulldstpath, exist_ok=True) + + fulldstfile = os.path.join(fulldstpath, filename) + + shutil.copy(os.path.join(srcpath, filename), fulldstfile) -for envName in ['wifi','bt']: - if buildEnv(envName, verbose=verbose) != 0: + print("image ", name) + + with open(fulldstfile, "rb") as f: + data = f.read() + image = { + # "name": name, + "size": os.path.getsize(fulldstfile), + "offset": offset, + "path": dstpath + '/' + filename, + "signature": { + "algorithm": "SHA2-256", + "value": hashlib.sha256(data).hexdigest() + } + } + if manifest['images'].get(name) != None: + print("Duplicate image name", name) sys.exit(1) - shutil.copy(os.path.join('.pio', 'build', envName, 'firmware.elf'), os.path.join(relPath, envName + '-' + 'firmware.elf')) + manifest['images'][name] = image + # manifest['images'].append(image) + +flashsize = "4m" + +mcu = "esp32" +for mcu in ['esp32']: + for envName in ['wifi','bt', 'noradio']: + if buildEnv(envName, verbose=verbose) != 0: + sys.exit(1) + buildDir = os.path.join('.pio', 'build', envName) + shutil.copy(os.path.join(buildDir, 'firmware.elf'), os.path.join(relPath, envName + '-' + 'firmware.elf')) + + addImage(mcu + '-' + envName + '-firmware', '0x10000', 'firmware.bin', buildDir, mcu + '/' + envName) + + if envName == 'wifi': + if buildFs('wifi', verbose=verbose) != 0: + sys.exit(1) + + # bootapp is a data partition that the bootloader and OTA use to determine which + # image to run. Its initial value is in a file "boot_app0.bin" in the platformio + # framework package. We copy it to the build directory so addImage can find it + bootappsrc = os.path.join(os.path.expanduser('~'),'.platformio','packages','framework-arduinoespressif32','tools','partitions', 'boot_app0.bin') + shutil.copy(bootappsrc, buildDir) + + addImage(mcu + '-' + envName + '-' + flashsize + '-filesystem', '0x3d0000', 'littlefs.bin', buildDir, mcu + '/' + envName + '/' + flashsize) + addImage(mcu + '-' + flashsize + '-partitions', '0x8000', 'partitions.bin', buildDir, mcu + '/' + flashsize) + addImage(mcu + '-bootloader', '0x1000', 'bootloader.bin', buildDir, mcu) + addImage(mcu + '-bootapp', '0xe000', 'boot_app0.bin', buildDir, mcu) + +def addSection(node, name, description, choice): + section = { + "name": name, + "description": description, + } + if choice != None: + section['choice-name'] = choice + section['choices'] = [] + node.append(section) + +def addMCU(name, description, choice=None): + addSection(manifest['installable']['choices'], name, description, choice) + +def addVariant(variant, description, choice=None): + node1 = manifest['installable']['choices'] + node1len = len(node1) + addSection(node1[node1len-1]['choices'], variant, description, choice) + +def addInstallable(install_type, erase, images): + for image in images: + if manifest['images'].get(image) == None: + # imagefiles = [obj for obj in manifest['images'] if obj['name'] == image] + # if len(imagefiles) == 0: + print("Missing image", image) + sys.exit(1) + # if len(imagefiles) > 1: + # print("Duplicate image", image) + # sys.exit(2) + + node1 = manifest['installable']['choices'] + node1len = len(node1) + node2 = node1[node1len-1]['choices'] + node2len = len(node2) + installable = { + "name": install_type["name"], + "description": install_type["description"], + "erase": erase, + "images": images + } + node2[node2len-1]['choices'].append(installable) + +fresh_install = { "name": "fresh-install", "description": "Complete FluidNC installation, erasing all previous data"} +firmware_update = { "name": "firmware-update", "description": "Update FluidNC to latest firmware version, preserving previous filesystem data."} +filesystem_update = { "name": "filesystem-update", "description": "Update FluidNC filesystem only, erasing previous filesystem data."} + +def makeManifest(): + addMCU("esp32", "ESP32-WROOM", "Firmware variant") + + addVariant("wifi", "Supports WiFi and WebUI", "Installation type") + addInstallable(fresh_install, True, ["esp32-4m-partitions", "esp32-bootloader", "esp32-bootapp", "esp32-wifi-firmware", "esp32-wifi-4m-filesystem"]) + addInstallable(firmware_update, False, ["esp32-wifi-firmware"]) + addInstallable(filesystem_update, False, ["esp32-wifi-4m-filesystem"]) + + addVariant("bt", "Supports Bluetooth serial", "Installation type") + addInstallable(fresh_install, True, ["esp32-4m-partitions", "esp32-bootloader", "esp32-bootapp", "esp32-bt-firmware"]) + addInstallable(firmware_update, False, ["esp32-bt-firmware"]) + + addVariant("noradio", "Supports neither WiFi nor Bluetooth", "Installation type") + addInstallable(fresh_install, True, ["esp32-4m-partitions", "esp32-bootloader", "esp32-bootapp", "esp32-noradio-firmware"]) + addInstallable(firmware_update, False, ["esp32-noradio-firmware"]) + +makeManifest() + +import json +def printManifest(): + print(json.dumps(manifest, indent=2)) + +with open(os.path.join(manifestRelPath, "manifest.json"), "w") as manifest_file: + json.dump(manifest, manifest_file, indent=2) + for platform in ['win64', 'posix']: print("Creating zip file for ", platform) diff --git a/example_configs/3axis_v4.yaml b/example_configs/3axis_v4.yaml deleted file mode 100644 index d859a2f5c..000000000 --- a/example_configs/3axis_v4.yaml +++ /dev/null @@ -1,95 +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_pin: gpio.13:low - - x: - steps_per_mm: 800 - max_rate_mm_per_min: 2000 - acceleration_mm_per_sec2: 25 - max_travel_mm: 1000 - homing: - cycle: 2 - mpos_mm: 10 - positive_direction: false - - motor0: - limit_all_pin: gpio.17:low:pu - stepstick: - direction_pin: gpio.14 - step_pin: gpio.12 - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate_mm_per_min: 2000 - acceleration_mm_per_sec2: 25 - max_travel_mm: 1000 - homing: - cycle: 2 - mpos_mm: 10 - positive_direction: false - - motor0: - limit_all_pin: gpio.4:low:pu - stepstick: - direction_pin: gpio.15 - step_pin: gpio.26 - motor1: - null_motor: - - z: - steps_per_mm: 800 - max_rate_mm_per_min: 2000 - acceleration_mm_per_sec2: 25 - max_travel_mm: 1000 - homing: - cycle: 1 - mpos_mm: 10 - positive_direction: true - - motor0: - limit_all_pin: gpio.16:low:pu - stepstick: - direction_pin: gpio.33 - step_pin: gpio.27 - motor1: - null_motor: - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -coolant: - flood_pin: gpio.25 - mist_pin: gpio.21 - - -probe: - pin: gpio.32:low:pu - -PWM: - pwm_hz: 5000 - output_pin: gpio.2 - enable_pin: gpio.22 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 0 - spindown_ms: 0 - tool_num: 0 - speed_map: 0=0% 10000=100% diff --git a/example_configs/6P_extn_XYZ_HBridge.yaml b/example_configs/6P_extn_XYZ_HBridge.yaml deleted file mode 100644 index ce80144a8..000000000 --- a/example_configs/6P_extn_XYZ_HBridge.yaml +++ /dev/null @@ -1,121 +0,0 @@ -board: 6 Pack -name: 6 Pack External XYZ HBridgeSpindle -meta: - -stepping: - engine: I2S_STREAM - idle_ms: 250 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 100.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - ms3_pin: i2so.3 - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 100.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 0.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - ms3_pin: i2so.6 - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - z: - steps_per_mm: 100.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 0.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - standard_stepper: - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -HBridgeSpindle: - pwm_hz: 5000 - output_cw_pin: gpio.4 - output_ccw_pin: gpio.16 - enable_pin: gpio.26 - disable_with_s0: false - spinup_ms: 0 - spindown_ms: 0 - tool_num: 100 - speed_map: 0=0.000% 10000=100.000% - \ No newline at end of file diff --git a/example_configs/6_Pack_2130_XYZABC.yaml b/example_configs/6_Pack_2130_XYZABC.yaml deleted file mode 100644 index 350085087..000000000 --- a/example_configs/6_Pack_2130_XYZABC.yaml +++ /dev/null @@ -1,314 +0,0 @@ -board: 6 Pack -name: 6 Pack tmc_2130 XYZABC -stepping: - engine: I2S_STREAM - idle_ms: 250 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.33 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.3 - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.32 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.6 - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.11 - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - a: - steps_per_mm: 53.400 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 960.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.34 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - tmc_2130: - cs_pin: i2so.14 - step_pin: I2SO.13 - direction_pin: I2SO.12 - disable_pin: I2SO.15 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - b: - steps_per_mm: 808.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 200.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.2 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - tmc_2130: - cs_pin: i2so.19 - step_pin: I2SO.18 - direction_pin: I2SO.17 - disable_pin: I2SO.16 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - c: - steps_per_mm: 808.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 200.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.25 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - tmc_2130: - cs_pin: i2so.22 - step_pin: I2SO.21 - direction_pin: I2SO.20 - disable_pin: I2SO.23 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: gpio.36 - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -coolant: - flood_pin: i2so.24 - mist_pin: i2so.27 - delay_ms: 0 - -probe: - pin: gpio.39 - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.14 - enable_pin: gpio.13 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% diff --git a/example_configs/6_Pack_OLED.yaml b/example_configs/6_Pack_OLED.yaml deleted file mode 100644 index e42682b9a..000000000 --- a/example_configs/6_Pack_OLED.yaml +++ /dev/null @@ -1,42 +0,0 @@ -board: 6 Pack -name: 6 Pack OLED -stepping: - engine: I2S_STATIC - -i2c0: - sda_pin: gpio.14 - scl_pin: gpio.13 - -oled: - i2c_num: 0 - i2c_address: 60 - width: 128 - height: 64 - radio_delay_ms: 1000 - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -axes: - x: - motor0: - null_motor: - - y: - motor0: - null_motor: - - z: - motor0: - null_motor: diff --git a/example_configs/6_Pack_solenoid.yaml b/example_configs/6_Pack_solenoid.yaml deleted file mode 100644 index a58976e73..000000000 --- a/example_configs/6_Pack_solenoid.yaml +++ /dev/null @@ -1,119 +0,0 @@ -board: 6 Pack -name: 6 Pack StepStick XYZABC -stepping: - engine: I2S_STREAM - idle_ms: 255 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.33 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - ms3_pin: i2so.3 - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.32 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - ms3_pin: i2so.6 - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - solenoid: - output_pin: gpio.26 - pwm_hz: 5000 - off_percent: 0.000 - pull_percent: 100.000 - hold_percent: 20.000 - pull_ms: 1000 - - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - - - - -start: - must_home: false - - diff --git a/example_configs/6_Pack_stepstick_XYZABC.yaml b/example_configs/6_Pack_stepstick_XYZABC.yaml deleted file mode 100644 index aa0fac064..000000000 --- a/example_configs/6_Pack_stepstick_XYZABC.yaml +++ /dev/null @@ -1,236 +0,0 @@ -board: 6 Pack -name: 6 Pack StepStick XYZABC -stepping: - engine: I2S_STREAM - idle_ms: 250 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.33 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - ms3_pin: i2so.3 - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.32 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - ms3_pin: i2so.6 - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - ms3_pin: i2so.11 - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - - a: - steps_per_mm: 53.400 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 960.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.34 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - stepstick: - ms3_pin: i2so.14 - step_pin: I2SO.13 - direction_pin: I2SO.12 - disable_pin: I2SO.15 - - b: - steps_per_mm: 808.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 200.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.2 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - stepstick: - ms3_pin: i2so.19 - step_pin: I2SO.18 - direction_pin: I2SO.17 - disable_pin: I2SO.16 - - c: - steps_per_mm: 808.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 200.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.25 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - stepstick: - ms3_pin: i2so.22 - step_pin: I2SO.21 - direction_pin: I2SO.20 - disable_pin: I2SO.23 - - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: gpio.36 - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -coolant: - flood_pin: i2so.24 - mist_pin: i2so.27 - delay_ms: 0 - -probe: - pin: gpio.39 - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.14 - enable_pin: gpio.13 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% diff --git a/example_configs/6_Pack_test.yaml b/example_configs/6_Pack_test.yaml deleted file mode 100644 index 27b6530dd..000000000 --- a/example_configs/6_Pack_test.yaml +++ /dev/null @@ -1,328 +0,0 @@ -board: 6 Pack -name: 6 Pack tmc_2130 XYZABC -stepping: - engine: I2S_STREAM - idle_ms: 250 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.33 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.3 - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.32 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.6 - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.11 - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - a: - steps_per_mm: 53.400 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 960.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.34 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - tmc_2130: - cs_pin: i2so.14 - step_pin: I2SO.13 - direction_pin: I2SO.12 - disable_pin: I2SO.15 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - b: - steps_per_mm: 808.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 200.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.2 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - tmc_5160: - cs_pin: i2so.19 - step_pin: I2SO.18 - direction_pin: I2SO.17 - disable_pin: I2SO.16 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - c: - steps_per_mm: 808.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 200.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.25 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 3.000 - tmc_5160: - cs_pin: i2so.22 - step_pin: I2SO.21 - direction_pin: I2SO.20 - disable_pin: I2SO.23 - spi_index: -1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: gpio.36 - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -coolant: - flood_pin: i2so.24 - mist_pin: i2so.27 - delay_ms: 0 - -probe: - pin: gpio.39 - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.14 - enable_pin: gpio.13 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% diff --git a/example_configs/6_pack_TMC2130_XYZ.yaml b/example_configs/6_pack_TMC2130_XYZ.yaml deleted file mode 100644 index a2d4a045c..000000000 --- a/example_configs/6_pack_TMC2130_XYZ.yaml +++ /dev/null @@ -1,200 +0,0 @@ -board: 6 Pack -name: 6 Pack StepStick XYZ -stepping: - engine: I2S_STREAM - idle_ms: 255 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.33:pu - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.3 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.750 - microsteps: 8 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: false - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.32:pu - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.6 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.750 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: i2so.11 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.750 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -coolant: - flood_pin: NO_PIN - mist_pin: NO_PIN - delay_ms: 0 - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.26 - enable_pin: gpio.4 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% diff --git a/example_configs/6_pack_TMC5160.yaml b/example_configs/6_pack_TMC5160.yaml deleted file mode 100644 index 6941bc2e0..000000000 --- a/example_configs/6_pack_TMC5160.yaml +++ /dev/null @@ -1,195 +0,0 @@ -board: 6 Pack -name: 6 Pack TMC5160 XYZ -stepping: - engine: I2S_STREAM - idle_ms: 255 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.33:pu - hard_limits: false - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.3 - r_sense_ohms: 0.075 - run_amps: 1.75 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: false - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.32:pu - hard_limits: false - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.6 - r_sense_ohms: 0.075 - run_amps: 1.75 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.11 - r_sense_ohms: 0.075 - run_amps: 1.750 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.26 - enable_pin: gpio.4 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% diff --git a/example_configs/6_pack_TMC5160_Huanyang.yaml b/example_configs/6_pack_TMC5160_Huanyang.yaml deleted file mode 100644 index baa79121d..000000000 --- a/example_configs/6_pack_TMC5160_Huanyang.yaml +++ /dev/null @@ -1,192 +0,0 @@ -board: 6 Pack -name: 6 Pack TMC5160 XYZ -stepping: - engine: I2S_STREAM - idle_ms: 255 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.33:pu - hard_limits: false - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.3 - r_sense_ohms: 0.075 - run_amps: 1.75 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: false - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.32:pu - hard_limits: false - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.6 - r_sense_ohms: 0.075 - run_amps: 1.75 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.11 - r_sense_ohms: 0.075 - run_amps: 1.750 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - -Huanyang: - uart: - txd_pin: gpio.26 - rxd_pin: gpio.16 - rts_pin: gpio.4 - baud: 9600 - mode: 8N1 - modbus_id: 1 - tool_num: 0 - speed_map: 0=0% 1000=0% 24000=100% - diff --git a/example_configs/6_pack_TMC5160_XYYZ.yaml b/example_configs/6_pack_TMC5160_XYYZ.yaml deleted file mode 100644 index 1d0e5b66e..000000000 --- a/example_configs/6_pack_TMC5160_XYYZ.yaml +++ /dev/null @@ -1,219 +0,0 @@ -board: 6 Pack -name: 6 Pack TMC5160 XYZ -stepping: - engine: I2S_STREAM - idle_ms: 250 - pulse_us: 2 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.33:pu - hard_limits: true - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.3 - r_sense_ohms: 0.075 - run_amps: 0.75 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: false - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.32:pu - hard_limits: true - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.6 - r_sense_ohms: 0.075 - run_amps: 0.75 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.35 - hard_limits: true - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.11 - r_sense_ohms: 0.075 - run_amps: 0.750 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.34 - hard_limits: true - pulloff_mm: 1.000 - tmc_5160: - cs_pin: i2so.14 - r_sense_ohms: 0.075 - run_amps: 0.750 - hold_amps: 0.50 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: I2SO.13 - direction_pin: I2SO.12 - disable_pin: I2SO.15 - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.26 - enable_pin: gpio.4 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% diff --git a/example_configs/6_pack_external_huanyang.yaml b/example_configs/6_pack_external_huanyang.yaml deleted file mode 100644 index 03ef5d413..000000000 --- a/example_configs/6_pack_external_huanyang.yaml +++ /dev/null @@ -1,160 +0,0 @@ -board: 6 Pack -name: 6 Pack External XYZ Haunyang -stepping: - engine: I2S_STREAM - idle_ms: 250 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - standard_stepper: - step_pin: I2SO.2 - direction_pin: I2SO.1 - disable_pin: I2SO.0 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.32:pu - hard_limits: false - pulloff_mm: 1.000 - standard_stepper: - step_pin: I2SO.5 - direction_pin: I2SO.4 - disable_pin: I2SO.7 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - standard_stepper: - step_pin: I2SO.10 - direction_pin: I2SO.9 - disable_pin: I2SO.8 - -i2so: - bck_pin: gpio.22 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -coolant: - flood_pin: NO_PIN - mist_pin: NO_PIN - delay_ms: 0 - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - -Huanyang: - uart: - txd_pin: gpio.26 - rxd_pin: gpio.16 - rts_pin: gpio.4 - baud: 9600 - mode: 8N1 - modbus_id: 1 - tool_num: 0 - speed_map: 0=0% 0=25% 6000=25% 24000=100% diff --git a/example_configs/BlackBox_X32_XYYZ-DOOR.yaml b/example_configs/BlackBox_X32_XYYZ-DOOR.yaml deleted file mode 100644 index f81454db3..000000000 --- a/example_configs/BlackBox_X32_XYYZ-DOOR.yaml +++ /dev/null @@ -1,131 +0,0 @@ -board: OpenBuilds BlackBox X32 -name: BlackBox_X32_XYYZ-DOOR -meta: Handcrafted by Shell M Shrader -stepping: - engine: RMT - idle_ms: 255 - pulse_us: 2 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: gpio.17:low - x: - steps_per_mm: 200.000 - max_rate_mm_per_min: 1000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - feed_mm_per_min: 100.000 - seek_mm_per_min: 500.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - standard_stepper: - step_pin: gpio.12 - direction_pin: gpio.14 - - y: - steps_per_mm: 200.000 - max_rate_mm_per_min: 1000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - feed_mm_per_min: 100.000 - seek_mm_per_min: 500.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.34 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - standard_stepper: - step_pin: gpio.27 - direction_pin: gpio.26 - - motor1: - standard_stepper: - step_pin: gpio.33 - direction_pin: gpio.32 - - z: - steps_per_mm: 200.000 - max_rate_mm_per_min: 300.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 50.000 - soft_limits: false - homing: - cycle: 1 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.39 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - standard_stepper: - step_pin: gpio.15 - direction_pin: gpio.2 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -probe: - pin: gpio.22:low - check_mode_start: true - -control: - safety_door_pin: gpio.16:pu - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -start: - must_home: false - -coolant: - mist_pin: gpio.21 - delay_ms: 0 - -PWM: - pwm_hz: 5000 - output_pin: gpio.25 - enable_pin: gpio.13 - direction_pin: gpio.4 - disable_with_s0: false - s0_with_disable: true - spinup_ms: 30000 - spindown_ms: 10000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% \ No newline at end of file diff --git a/example_configs/MKS_DLC32_21_XYZ.yaml b/example_configs/MKS_DLC32_21_XYZ.yaml deleted file mode 100644 index b6774d793..000000000 --- a/example_configs/MKS_DLC32_21_XYZ.yaml +++ /dev/null @@ -1,157 +0,0 @@ -board: MKS-DLC32 V2.1 -name: K40 Laser -meta: (01.01.2022) by Skorpi - -kinematics: - Cartesian: - -stepping: - engine: I2S_STATIC - idle_ms: 0 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 -axes: - shared_stepper_disable_pin: I2SO.0 - x: - steps_per_mm: 157.750 - max_rate_mm_per_min: 18000.000 - acceleration_mm_per_sec2: 1500.000 - max_travel_mm: 325.000 - soft_limits: true - homing: - cycle: 1 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 300.000 - seek_mm_per_min: 5000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.36 - hard_limits: false - pulloff_mm: 2.000 - stepstick: - step_pin: I2SO.1 - direction_pin: I2SO.2 - - y: - steps_per_mm: 157.750 - max_rate_mm_per_min: 12000.000 - acceleration_mm_per_sec2: 300.000 - max_travel_mm: 220.000 - soft_limits: true - homing: - cycle: 1 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 300.000 - seek_mm_per_min: 5000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35 - hard_limits: false - pulloff_mm: 2.000 - stepstick: - step_pin: I2SO.5 - direction_pin: I2SO.6:low - - z: - steps_per_mm: 157.750 - max_rate_mm_per_min: 12000.000 - acceleration_mm_per_sec2: 500.000 - max_travel_mm: 80.000 - soft_limits: true - homing: - cycle: 0 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 300.000 - seek_mm_per_min: 1000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.34 - hard_limits: false - pulloff_mm: 1.000 - stepstick: - step_pin: I2SO.3 - direction_pin: I2SO.4 - -i2so: - bck_pin: gpio.16 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.12 - mosi_pin: gpio.13 - sck_pin: gpio.14 - -sdcard: - cs_pin: gpio.15 - card_detect_pin: NO_PIN - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: gpio.33:low:pu - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -macros: - startup_line0: - startup_line1: - macro0: $SD/Run=lasertest.gcode - macro1: $SD/Run=home.gcode - macro2: - macro3: - -coolant: - flood_pin: NO_PIN - mist_pin: NO_PIN - delay_ms: 0 - -probe: - pin: gpio.22 - check_mode_start: true - -Laser: - pwm_hz: 5000 - #L on Beeper / IN on TTL - output_pin: gpio.32 - enable_pin: I2SO.7 - disable_with_s0: false - s0_with_disable: false - tool_num: 0 - speed_map: 0=0.000% 0=12.500% 1700=100.000% -# 135=0mA 270=5mA 400=10mA 700=16mA -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - -# 5,18,19,22,23,25,26,27,32,33,39,I2SO.7 -# SDA 0 / SCL 4 diff --git a/example_configs/MKS_DLC32_2_ABC.yaml b/example_configs/MKS_DLC32_2_ABC.yaml deleted file mode 100644 index 4f0899ec3..000000000 --- a/example_configs/MKS_DLC32_2_ABC.yaml +++ /dev/null @@ -1,121 +0,0 @@ -board: MKS DLC32 2.0 -name: MKS DLC32 XYZ -meta: (12/2/2021) B. Dring for diruuu -stepping: - engine: I2S_STREAM - idle_ms: 250 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: i2so.0 - x: - steps_per_mm: 100.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.36 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - step_pin: i2so.1 - direction_pin: I2SO.2 - - y: - steps_per_mm: 100.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 3 - positive_direction: true - mpos_mm: 0.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - step_pin: I2SO.5 - direction_pin: I2SO.6 - - z: - steps_per_mm: 100.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 0.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.34 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - stepstick: - step_pin: I2SO.3 - direction_pin: I2SO.4 - -i2so: - bck_pin: gpio.16 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.12 - mosi_pin: gpio.13 - sck_pin: gpio.14 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.15 - -probe: - pin: gpio.2 - check_mode_start: true - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.22 - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 12000=100.000% diff --git a/example_configs/MKS_DLC32_v21_laser.yaml b/example_configs/MKS_DLC32_v21_laser.yaml deleted file mode 100644 index b6d917efa..000000000 --- a/example_configs/MKS_DLC32_v21_laser.yaml +++ /dev/null @@ -1,202 +0,0 @@ -# Basic configuration file for X/Y Laser using GT2 belts 1.8ºNEMA motors -# at 16 microSteps and 16 Tooth pulleys - -board: MKS-DLC32 V2.1 -name: 3dpBurner3 -meta: villamany 30/Jan/2023 - -kinematics: - Cartesian: - -stepping: - engine: I2S_STATIC - idle_ms: 255 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 -axes: - shared_stepper_disable_pin: I2SO.0 - x: - steps_per_mm: 100 - max_rate_mm_per_min: 16000 - acceleration_mm_per_sec2: 1500 - max_travel_mm: 895 - soft_limits: false - homing: - cycle: 0 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 500.000 - seek_mm_per_min: 16000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.36:low - hard_limits: false - pulloff_mm: 2.000 - stepstick: - step_pin: I2SO.1 - direction_pin: I2SO.2:low - - y: - steps_per_mm: 100 - max_rate_mm_per_min: 16000 - acceleration_mm_per_sec2: 1500 - max_travel_mm: 880 - soft_limits: false - homing: - cycle: 0 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 500.000 - seek_mm_per_min: 16000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.35:low - hard_limits: false - pulloff_mm: 2.000 - stepstick: - step_pin: I2SO.5 - direction_pin: I2SO.6:high - - z: - steps_per_mm: 80 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 500.000 - max_travel_mm: 80.000 - soft_limits: true - homing: - cycle: 0 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 200.000 - seek_mm_per_min: 500.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.34 - hard_limits: false - pulloff_mm: 1.000 - stepstick: - step_pin: I2SO.3 - direction_pin: I2SO.4 - -i2so: - bck_pin: gpio.16 - data_pin: gpio.21 - ws_pin: gpio.17 - -spi: - miso_pin: gpio.12 - mosi_pin: gpio.13 - sck_pin: gpio.14 - -sdcard: - cs_pin: gpio.15 - card_detect_pin: NO_PIN -# card_detect_pin: gpio.39 - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -coolant: - flood_pin: NO_PIN - mist_pin: NO_PIN - delay_ms: 0 - -#probe: -# pin: gpio.22 -# check_mode_start: true - -Laser: - pwm_hz: 5000 - output_pin: gpio.32 - disable_with_s0: false - s0_with_disable: false - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% -#PWM: -# direction_pin: NO_PIN -# spinup_ms: 1000 -# spindown_ms: 1000 - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - #Beeper connector. Command: "M62 P0" turn beeper On. - #"G4 P0.5" wait for 0.5s. "M63 P0" turn beeper OFF - digital0_pin: I2SO.7 - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - - -#MKS DLC32 v2.1 pinMap - -# X- gpio.36 -# SD_DET gpio.39 -# Z- gpio.34 -# Y- gpio.35 -# SPINDLE PWM gpio.32 -# LCD_RS gpio.33 -# LCD_CS_INV gpio.25 -# LCD_TOUCH_CS_INV gpio.26 -# LCD_RST_INV gpio.27 -# SD_SCK gpio.14 -# SD_DO gpio.12 -# SD_DI gpio.13 -# SD_CS gpio.15 -# I2C_SDA gpio.0 -# I2C_SCL gpio.4 -# I2S_BCK gpio.16 -# I2S_WS gpio.17 -# LCD_EN_INV gpio.5 -# LCD_SCK gpio.18 -# LCD_MISO gpio.19 -# I2S_DATA gpio.21 -# RXD0 gpio.3 -# TXD0 gpio.1 -# Probe gpio.22 -# LCD_MOSI gpio.23 - -# XYZ_EN I2SO.0 -# X_STEP I2SO.1 -# X_DIR I2SO.2 -# Z_STEP I2SO.3 -# Z_DIR I2SO.4 -# Y_STEP I2SO.5 -# Y_DIR I2SO.6 -# BEEPER I2SO.7 - - diff --git a/example_configs/MKS_TinyBee_1_XYZAB.yaml b/example_configs/MKS_TinyBee_1_XYZAB.yaml deleted file mode 100644 index 81818212f..000000000 --- a/example_configs/MKS_TinyBee_1_XYZAB.yaml +++ /dev/null @@ -1,227 +0,0 @@ -board: MKS TinyBee V1.0_001 -name: K40 Laser -meta: (01.02.2022) by Skorpi - -kinematics: - Cartesian: - -stepping: - engine: I2S_STATIC - idle_ms: 0 - pulse_us: 4 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - x: - # X - steps_per_mm: 157.750 - max_rate_mm_per_min: 18000.000 - acceleration_mm_per_sec2: 1500.000 - max_travel_mm: 325.000 - soft_limits: true - homing: - cycle: 0 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 300.000 - seek_mm_per_min: 5000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.33 - hard_limits: false - pulloff_mm: 2.000 - stepstick: - step_pin: I2SO.1 - direction_pin: I2SO.2 - disable_pin: I2SO.0 - - y: - # Y - steps_per_mm: 157.750 - max_rate_mm_per_min: 12000.000 - acceleration_mm_per_sec2: 300.000 - max_travel_mm: 220.000 - soft_limits: true - homing: - cycle: 1 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 300.000 - seek_mm_per_min: 5000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.32 - hard_limits: false - pulloff_mm: 2.000 - stepstick: - step_pin: I2SO.4 - direction_pin: I2SO.5 - disable_pin: I2SO.3 - - z: - # Z - steps_per_mm: 157.750 - max_rate_mm_per_min: 12000.000 - acceleration_mm_per_sec2: 500.000 - max_travel_mm: 80.000 - soft_limits: true - homing: - cycle: 0 - positive_direction: false - mpos_mm: 0.000 - feed_mm_per_min: 300.000 - seek_mm_per_min: 1000.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.22 - hard_limits: false - pulloff_mm: 1.000 - stepstick: - step_pin: I2SO.7 - direction_pin: I2SO.8 - disable_pin: I2SO.6 - -# a: -# # E0 -# steps_per_mm: 157.750 -# max_rate_mm_per_min: 18000.000 -# acceleration_mm_per_sec2: 1500.000 -# max_travel_mm: 325.000 -# soft_limits: true -# homing: -# cycle: 1 -# positive_direction: false -# mpos_mm: 0.000 -# feed_mm_per_min: 300.000 -# seek_mm_per_min: 5000.000 -# settle_ms: 500 -# seek_scaler: 1.100 -# feed_scaler: 1.100 -# -# motor0: -# limit_neg_pin: gpio.35 -# hard_limits: false -# pulloff_mm: 2.000 -# stepstick: -# step_pin: I2SO.10 -# direction_pin: I2SO.11:low -# disable_pin: I2SO.9 - -# b: -# # E1 -# steps_per_mm: 157.750 -# max_rate_mm_per_min: 12000.000 -# acceleration_mm_per_sec2: 500.000 -# max_travel_mm: 80.000 -# soft_limits: true -# homing: -# cycle: 0 -# positive_direction: false -# mpos_mm: 0.000 -# feed_mm_per_min: 300.000 -# seek_mm_per_min: 1000.000 -# settle_ms: 500 -# seek_scaler: 1.100 -# feed_scaler: 1.100 -# -# motor0: -# limit_neg_pin: gpio.2 -# hard_limits: false -# pulloff_mm: 1.000 -# stepstick: -# step_pin: I2SO.13 -# direction_pin: I2SO.14 -# disable_pin: I2SO.12 - -i2so: - bck_pin: gpio.25 - data_pin: gpio.27 - ws_pin: gpio.26 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - # EXP1 BTN_ENC - macro0_pin: gpio.4:low:pu - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -macros: - startup_line0: - startup_line1: - macro0: $SD/Run=lasertest.gcode - macro1: $SD/Run=home.gcode - macro2: - macro3: - -coolant: - flood_pin: NO_PIN - mist_pin: NO_PIN - delay_ms: 0 - -#probe: -# pin: gpio.2 -# check_mode_start: true - -Laser: - pwm_hz: 5000 - # EXP1 BTN_ENC - output_pin: gpio.13 - # FAN1 - enable_pin: I2SO.16 - disable_with_s0: false - s0_with_disable: false - tool_num: 0 - speed_map: 0=0.000% 0=12.500% 1700=100.000% -# 135=0mA 270=5mA 400=10mA 700=16mA -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - - # USB TX0(1) RX0(3) - # J3-> TX2(17) RX2(16) - # J1-> I2SO.23 I2SO.22 - # TH1(36) TH2(34) THB(39) - # HE0(I2SO.17) HE1(I2SO.18) HBED(I2SO.16) - # FAN1(I2SO.19) FAN2(I2SO.20) - # EXP1 EXP2 - #(BEEPER) I2SO.21 | 1 2 | 13 (BTN_ENC) (SPI MISO) 19 | 1 2 | 18 (SPI SCK) - # (LCD_EN) 21 | 3 4 | 4 (LCD_RS) (BTN_EN1) 14 | 3 4 | 5 (SPI CS) - # (LCD_D4) 0 | 5 6 16 (LCD_D5) (BTN_EN2) 12 | 5 6 23 (SPI MOSI) - # (LCD_D6) 15 | 7 8 | 17 (LCD_D7) (SPI_DET) 34 | 7 8 | RESET - # GND | 9 10 | 5V GND | 9 10 | 3.3V diff --git a/example_configs/README.md b/example_configs/README.md new file mode 100644 index 000000000..58e4183a3 --- /dev/null +++ b/example_configs/README.md @@ -0,0 +1,4 @@ +### The config files have moved to their own GitHub repo + +[See this GitHub repo](https://github.com/bdring/fluidnc-config-files). + diff --git a/example_configs/TMC2130_SPI_Daisy.yaml b/example_configs/TMC2130_SPI_Daisy.yaml deleted file mode 100644 index 8d244d381..000000000 --- a/example_configs/TMC2130_SPI_Daisy.yaml +++ /dev/null @@ -1,195 +0,0 @@ -board: 4 Axis SPI Daisy -name: 4 Axis SPI Daisy Test -stepping: - engine: RMT - idle_ms: 255 - pulse_us: 2 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: NO_PIN - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - cs_pin: gpio.17 - spi_index: 1 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.750 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: true - step_pin: gpio.12 - direction_pin: gpio.14 - disable_pin: NO_PIN - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - spi_index: 2 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.750 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: true - step_pin: gpio.27 - direction_pin: gpio.26 - disable_pin: NO_PIN - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - spi_index: 3 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.750 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: true - step_pin: gpio.15 - direction_pin: gpio.2 - disable_pin: NO_PIN - - a: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2130: - spi_index: 4 - r_sense_ohms: 0.110 - run_amps: 0.750 - hold_amps: 0.750 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: true - step_pin: gpio.33 - direction_pin: gpio.32 - disable_pin: NO_PIN - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -start: - must_home: false diff --git a/example_configs/TMC2130_pen.yaml b/example_configs/TMC2130_pen.yaml deleted file mode 100644 index 074293340..000000000 --- a/example_configs/TMC2130_pen.yaml +++ /dev/null @@ -1,127 +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_pin: gpio.13:high - - x: - steps_per_mm: 800 - max_rate_mm_per_min: 2000 - acceleration_mm_per_sec2: 25 - max_travel_mm: 1000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_all_pin: gpio.32:low:pu - tmc_2130: - direction_pin: gpio.26 - step_pin: gpio.12 - cs_pin: gpio.17 - r_sense_ohms: 0.110 - run_amps: 0.250 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate_mm_per_min: 2000 - acceleration_mm_per_sec2: 25 - max_travel_mm: 1000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_all_pin: NO_PIN - tmc_2130: - direction_pin: gpio.25 - step_pin: gpio.14 - cs_pin: gpio.16 - r_sense_ohms: 0.110 - run_amps: 0.250 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - motor1: - null_motor: - - z: - steps_per_mm: 400 - max_rate_mm_per_min: 1000 - acceleration_mm_per_sec2: 50 - max_travel_mm: 5.00 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 5 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - rc_servo: - pwm_hz: 50 - output_pin: gpio.27 - min_pulse_us: 2100 - max_pulse_us: 1000 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -coolant: - flood_pin: NO_PIN - mist_pin: NO_PIN - -probe: - pin: NO_PIN - - diff --git a/example_configs/TMC2209.yaml b/example_configs/TMC2209.yaml deleted file mode 100644 index 37a9510cb..000000000 --- a/example_configs/TMC2209.yaml +++ /dev/null @@ -1,174 +0,0 @@ -board: TMC2209 4X -name: TMC2209 XYZA -stepping: - engine: RMT - idle_ms: 255 - pulse_us: 2 - dir_delay_us: 1 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: gpio.25 - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - step_pin: gpio.26 - direction_pin: gpio.27 - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.34 - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - step_pin: gpio.33 - direction_pin: gpio.32 - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: gpio.39 - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - step_pin: gpio.2 - direction_pin: gpio.14 - -a: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - step_pin: gpio.16 - direction_pin: gpio.15 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - must_home: false - -PWM: - pwm_hz: 5000 - output_pin: gpio.4 - enable_pin: gpio.13 - direction_pin: gpio.17 - disable_with_s0: false - s0_with_disable: true - spinup_ms: 1000 - spindown_ms: 1000 - tool_num: 0 - speed_map: 0=0.000% 1000=100.000% diff --git a/example_configs/TMC2209_corexy.yaml b/example_configs/TMC2209_corexy.yaml deleted file mode 100644 index 97eb3916c..000000000 --- a/example_configs/TMC2209_corexy.yaml +++ /dev/null @@ -1,157 +0,0 @@ -board: TMC2209 4X -name: TMC2209 XYZA -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 255 - pulse_us: 2 - dir_delay_us: 1 - disable_delay_us: 0 - -kinematics: - corexy: - -uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.25:high - - x: - steps_per_mm: 100 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 80 - soft_limits: true - homing: - cycle: 1 - mpos_mm: 78 - positive_direction: true - feed_mm_per_min: 400.000 - seek_mm_per_min: 1200.000 - settle_ms: 200 - - motor0: - limit_pos_pin: gpio.35:low - hard_limits: false - pulloff_mm: 2.000 - tmc_2209: - uart_num: 1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.250 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.26 - direction_pin: gpio.27:low - disable_pin: NO_PIN - - motor1: - null_motor: - - y: - steps_per_mm: 100 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 105 - - homing: - cycle: 2 - mpos_mm: 103 - positive_direction: true - feed_mm_per_min: 400.000 - seek_mm_per_min: 1200.000 - settle_ms: 200 - - motor0: - limit_pos_pin: gpio.34:low - hard_limits: false - pulloff_mm: 2.00 - tmc_2209: - uart_num: 1 - addr: 1 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.250 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.33 - direction_pin: gpio.32 - disable_pin: NO_PIN - motor1: - null_motor: - - z: - steps_per_mm: 100 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 50 - max_travel_mm: 25 - - homing: - cycle: 0 - mpos_mm: 23 - positive_direction: true - feed_mm_per_min: 400.000 - seek_mm_per_min: 800.000 - settle_ms: 500 - - motor0: - limit_pos_pin: gpio.39:low - hard_limits: false - pulloff_mm: 4.00 - tmc_2209: - uart_num: 1 - addr: 2 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.200 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.2 - direction_pin: gpio.14 - disable_pin: NO_PIN - - motor1: - null_motor: - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - - -start: - must_home: false - diff --git a/example_configs/TMC2209_pen.yaml b/example_configs/TMC2209_pen.yaml deleted file mode 100644 index 6059dbdec..000000000 --- a/example_configs/TMC2209_pen.yaml +++ /dev/null @@ -1,174 +0,0 @@ -board: TMC2209 Pen -name: TMC2209 Pen -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 250 - pulse_us: 2 - dir_delay_us: 1 - disable_delay_us: 0 - -uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.13 - x: - steps_per_mm: 80.000 - max_rate_mm_per_min: 30000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.33 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.500 - microsteps: 4 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: false - step_pin: gpio.12 - direction_pin: gpio.26 - disable_pin: NO_PIN - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - null_motor: - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.32 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 1 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.500 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.14 - direction_pin: gpio.25 - disable_pin: NO_PIN - - z: - steps_per_mm: 320.000 - max_rate_mm_per_min: 1000.000 - acceleration_mm_per_sec2: 25.000 - max_travel_mm: 200.000 - soft_limits: false - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - check_limits: true - -Laser: - pwm_hz: 5000 - output_pin: gpio.27 - enable_pin: gpio.17 - disable_with_s0: false - s0_with_disable: true - tool_num: 100 - speed_map: 0=0.000% 255=100.000% diff --git a/example_configs/TMC2209_pen_SG.yaml b/example_configs/TMC2209_pen_SG.yaml deleted file mode 100644 index 66f8641b1..000000000 --- a/example_configs/TMC2209_pen_SG.yaml +++ /dev/null @@ -1,182 +0,0 @@ -board: TMC2209 Pen -name: TMC2209 Pen -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 250 - pulse_us: 2 - dir_delay_us: 1 - disable_delay_us: 0 - -uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.13 - x: - steps_per_mm: 80.000 - max_rate_mm_per_min: 30000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.4 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 1.00 - hold_amps: 0.500 - microsteps: 4 - stallguard: 30 - stallguard_debug: true - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StallGuard - use_enable: false - step_pin: gpio.12 - direction_pin: gpio.26 - disable_pin: NO_PIN - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - null_motor: - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.15 - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 1 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.500 - microsteps: 16 - stallguard: 10 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StallGuard - use_enable: false - step_pin: gpio.14 - direction_pin: gpio.25 - disable_pin: NO_PIN - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - null_motor: - - z: - steps_per_mm: 320.000 - max_rate_mm_per_min: 1000.000 - acceleration_mm_per_sec2: 25.000 - max_travel_mm: 200.000 - soft_limits: false - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -control: - safety_door_pin: NO_PIN - reset_pin: NO_PIN - feed_hold_pin: NO_PIN - cycle_start_pin: NO_PIN - macro0_pin: NO_PIN - macro1_pin: NO_PIN - macro2_pin: NO_PIN - macro3_pin: NO_PIN - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -user_outputs: - analog0_pin: NO_PIN - analog1_pin: NO_PIN - analog2_pin: NO_PIN - analog3_pin: NO_PIN - analog0_hz: 5000 - analog1_hz: 5000 - analog2_hz: 5000 - analog3_hz: 5000 - digital0_pin: NO_PIN - digital1_pin: NO_PIN - digital2_pin: NO_PIN - digital3_pin: NO_PIN - -start: - check_limits: true - -Laser: - pwm_hz: 5000 - output_pin: gpio.27 - enable_pin: gpio.17 - disable_with_s0: false - s0_with_disable: true - tool_num: 100 - speed_map: 0=0.000% 255=100.000% diff --git a/example_configs/WallPlotter.yaml b/example_configs/WallPlotter.yaml deleted file mode 100644 index 82452986c..000000000 --- a/example_configs/WallPlotter.yaml +++ /dev/null @@ -1,110 +0,0 @@ -name: "ESP32 Dev Controller V4" -board: "WallPlotter ArduinoCNC Shield" - -kinematics: - WallPlotter: - left_axis: 0 - left_anchor_x: -428.000 - left_anchor_y: 520.00 - right_axis: 1 - right_anchor_x: 428.000 - right_anchor_y: 520.00 - segment_length: 2.0 - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 10 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: gpio.13 - - x: - steps_per_mm: 8.250 - max_rate_mm_per_min: 4000 - acceleration_mm_per_sec2: 400 - max_travel_mm: 4000 - homing: - cycle: 0 - mpos_mm: 0 - positive_direction: false - - motor0: - stepstick: - direction_pin: gpio.25 - step_pin: gpio.15 - - y: - steps_per_mm: 8.250 - max_rate_mm_per_min: 4000 - acceleration_mm_per_sec2: 400 - max_travel_mm: 4000 - homing: - cycle: 0 - mpos_mm: 0 - positive_direction: false - - motor0: - limit_all_pin: NO_PIN - stepstick: - direction_pin: gpio.26 - step_pin: gpio.2 - - # z: - # steps_per_mm: 2000 - # max_rate_mm_per_min: 500 - # acceleration_mm_per_sec2: 100 - # max_travel_mm: 5 - # homing: - # cycle: 0 - # mpos_mm: 0 - # positive_direction: false - - # motor0: - # rc_servo: - # pwm_hz: 50 - # output_pin: gpio.27 - # min_pulse_us: 700 - # max_pulse_us: 2200 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -coolant: - flood_pin: NO_PIN - mist_pin: NO_PIN - -probe: - pin: gpio.32:low:pu - -# Control pen up/down using a servo that is configured to look like a spindle -# A cheap blue 9g chinese servo was used. -# Different min_pulse_us and max_pulse_us may need to be used for other brands... -# -# As configured the servo will then respond as follows -# M3 S0 is pen up from paper -# M3 S255 is pen down on paper -# If you need to invert motion of servo, invert the values for min_pulse_us and max_pulse_us -besc: - pwm_hz: 50 - output_pin: gpio.21 - enable_pin: NO_PIN - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 2000 - spindown_ms: 2000 - tool_num: 100 - speed_map: 0=0.000% 255=100.000% - min_pulse_us: 700 - max_pulse_us: 2200 - - diff --git a/example_configs/fluidnc_pen_laser.yaml b/example_configs/fluidnc_pen_laser.yaml deleted file mode 100644 index e490914af..000000000 --- a/example_configs/fluidnc_pen_laser.yaml +++ /dev/null @@ -1,136 +0,0 @@ -name: "TMC2130 XY Servo Laser" -board: "FluidNC Pen/Laser" - -stepping: - engine: RMT - idle_ms: 255 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: gpio.13:high - - x: - steps_per_mm: 800 - max_rate_mm_per_min: 2000 - acceleration_mm_per_sec2: 25 - max_travel_mm: 1000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.39:low - tmc_2130: - direction_pin: gpio.12 - step_pin: gpio.14 - cs_pin: gpio.16 - r_sense_ohms: 0.110 - run_amps: 0.250 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate_mm_per_min: 2000 - acceleration_mm_per_sec2: 25 - max_travel_mm: 1000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: gpio.36:low - tmc_2130: - direction_pin: gpio.26 - step_pin: gpio.25 - cs_pin: gpio.17 - r_sense_ohms: 0.110 - run_amps: 0.250 - hold_amps: 0.250 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - motor1: - null_motor: - - z: - steps_per_mm: 100 - max_rate_mm_per_min: 1000 - acceleration_mm_per_sec2: 50 - max_travel_mm: 5.00 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 5 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - rc_servo: - pwm_hz: 50 - output_pin: gpio.22 - min_pulse_us: 1000 - max_pulse_us: 2100 - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -coolant: - flood_pin: NO_PIN - mist_pin: gpio.21 - -probe: - pin: gpio.32:low:pu - -Laser: - pwm_hz: 5000 - output_pin: gpio.27 - enable_pin: gpio.2 - disable_with_s0: false - s0_with_disable: true - tool_num: 0 - speed_map: 0=0.000% 255=100.000% - - diff --git a/example_configs/fysetc_corexy.yaml b/example_configs/fysetc_corexy.yaml deleted file mode 100644 index eada3667d..000000000 --- a/example_configs/fysetc_corexy.yaml +++ /dev/null @@ -1,148 +0,0 @@ -name: "Fysetc Ant CoreXY" -board: "Fysetc E4" - -stepping: - engine: RMT - idle_ms: 255 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -kinematics: - corexy: - -axes: - shared_stepper_disable_pin: gpio.25:high - - x: - steps_per_mm: 100.000 - max_rate_mm_per_min: 4000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 200.000 - seek_mm_per_min: 400.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_all_pin: gpio.34:low - hard_limits: true - pulloff_mm: 1.000 - tmc_2209: - uart: - txd_pin: gpio.22 - rxd_pin: gpio.21 - baud: 115200 - mode: 8N1 - addr: 1 - r_sense_ohms: 0.110 - run_amps: 1.500 - hold_amps: 0.500 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: false - step_pin: gpio.27 - direction_pin: gpio.26 - disable_pin: NO_PIN - - y: - steps_per_mm: 100.000 - max_rate_mm_per_min: 4000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: true - mpos_mm: 150.000 - feed_mm_per_min: 200.000 - seek_mm_per_min: 400.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_all_pin: gpio.35:low - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - addr: 3 - r_sense_ohms: 0.110 - run_amps: 1.5200 - hold_amps: 0.500 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: CoolStep - homing_mode: CoolStep - use_enable: false - step_pin: gpio.33 - direction_pin: gpio.32:low - disable_pin: NO_PIN - - z: - steps_per_mm: 100.000 - max_rate_mm_per_min: 4000.000 - acceleration_mm_per_sec2: 50.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 0 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_all_pin: gpio.15:low - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - addr: 0 - r_sense_ohms: 0.110 - run_amps: 1.200 - hold_amps: 0.500 - microsteps: 16 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StallGuard - homing_mode: StallGuard - use_enable: false - step_pin: gpio.14 - direction_pin: gpio.12 - disable_pin: NO_PIN - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -start: - must_home: false - deactivate_parking: false - check_limits: false diff --git a/example_configs/midtbot_stepstick.yaml b/example_configs/midtbot_stepstick.yaml deleted file mode 100644 index 9addf8c24..000000000 --- a/example_configs/midtbot_stepstick.yaml +++ /dev/null @@ -1,86 +0,0 @@ -name: "midtbot stepstick" -board: "midtbot" - -kinematics: - midtbot: - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -axes: - shared_stepper_disable_pin: gpio.13:high - - x: - steps_per_mm: 100 - max_rate_mm_per_min: 8000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 1000 - homing: - cycle: 3 - mpos_mm: 5 - feed_mm_per_min: 500.000 - seek_mm_per_min: 2000.000 - positive_direction: false - - motor0: - limit_all_pin: gpio.2:low:pu - pulloff_mm: 1.000 - stepstick: - direction_pin: gpio.26:high - step_pin: gpio.12 - motor1: - null_motor: - - y: - steps_per_mm: 100 - max_rate_mm_per_min: 8000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 1000 - homing: - cycle: 2 - mpos_mm: 100 - feed_mm_per_min: 500.000 - seek_mm_per_min: 2000.000 - positive_direction: true - - motor0: - limit_all_pin: gpio.4:low:pu - pulloff_mm: 1.000 - stepstick: - direction_pin: gpio.25:low - step_pin: gpio.14 - motor1: - null_motor: - - z: - steps_per_mm: 100 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 5 - homing: - cycle: 1 - mpos_mm: 0 - positive_direction: true - - motor0: - rc_servo: - pwm_hz: 50 - output_pin: gpio.27 - min_pulse_us: 1000 - max_pulse_us: 2000 - - motor1: - null_motor: - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN diff --git a/example_configs/test_drive_SD.yaml b/example_configs/test_drive_SD.yaml deleted file mode 100644 index f08eb4b26..000000000 --- a/example_configs/test_drive_SD.yaml +++ /dev/null @@ -1,55 +0,0 @@ -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_pin: NO_PIN - x: - steps_per_mm: 320.000 - max_rate_mm_per_min: 1000.000 - acceleration_mm_per_sec2: 25.000 - max_travel_mm: 200.000 - soft_limits: false - - y: - steps_per_mm: 320.000 - max_rate_mm_per_min: 1000.000 - acceleration_mm_per_sec2: 25.000 - max_travel_mm: 200.000 - soft_limits: false - - z: - steps_per_mm: 320.000 - max_rate_mm_per_min: 1000.000 - acceleration_mm_per_sec2: 25.000 - max_travel_mm: 200.000 - soft_limits: false - -spi: - miso_pin: NO_PIN - mosi_pin: NO_PIN - sck_pin: NO_PIN - - -probe: - pin: NO_PIN - check_mode_start: true - -macros: - startup_line0: - startup_line1: - macro0: - macro1: - macro2: - macro3: - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -NoSpindle: diff --git a/example_configs/tmc2209_10V.yaml b/example_configs/tmc2209_10V.yaml deleted file mode 100644 index 19bf960e0..000000000 --- a/example_configs/tmc2209_10V.yaml +++ /dev/null @@ -1,170 +0,0 @@ -name: "ESP32 Dev Controller V4" -board: "ESP32 Dev Controller V4" -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.25:high - - x: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - homing: - cycle: 1 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_pos_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.500 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.26 - direction_pin: gpio.27 - disable_pin: NO_PIN - - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.34 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.33 - direction_pin: gpio.32 - microsteps: 16 - uart_num: 1 - addr: 1 - - motor1: - null_motor: - - z: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.39 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.2 - direction_pin: gpio.14 - uart_num: 1 - addr: 2 - - motor1: - null_motor: - - - a: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.36 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.16 - direction_pin: gpio.15 - uart_num: 1 - addr: 3 - - motor1: - null_motor: - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -probe: - pin: NO_PIN - -10V: - output_pin: gpio.4 - forward_pin: gpio.13 - reverse_pin: gpio.17 - spinup_ms: 0 - spindown_ms: 0 - tool_num: 0 - speed_map: 0=0% 1000=0% 24000=100% diff --git a/example_configs/tmc2209_BESC.yaml b/example_configs/tmc2209_BESC.yaml deleted file mode 100644 index a638d4246..000000000 --- a/example_configs/tmc2209_BESC.yaml +++ /dev/null @@ -1,175 +0,0 @@ -name: "ESP32 Dev Controller V4" -board: "ESP32 Dev Controller V4" -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.25:high - - x: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - homing: - cycle: 1 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_pos_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.500 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.26 - direction_pin: gpio.27 - disable_pin: NO_PIN - - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.34 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.33 - direction_pin: gpio.32 - microsteps: 16 - uart_num: 1 - addr: 1 - - motor1: - null_motor: - - z: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.39 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.2 - direction_pin: gpio.14 - uart_num: 1 - addr: 2 - - motor1: - null_motor: - - - a: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.36 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.16 - direction_pin: gpio.15 - uart_num: 1 - addr: 3 - - motor1: - null_motor: - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -probe: - pin: NO_PIN - -besc: - pwm_hz: 50 - output_pin: gpio.4 - enable_pin: NO_PIN - direction_pin: NO_PIN - disable_with_s0: false - s0_with_disable: true - spinup_ms: 0 - spindown_ms: 0 - tool_num: 100 - speed_map: 0=0.000% 0=20.000% 4000=20.000% 20000=100.000% - min_pulse_us: 900 - max_pulse_us: 2200 diff --git a/example_configs/tmc2209_huanyang.yml b/example_configs/tmc2209_huanyang.yml deleted file mode 100644 index 8dda93dc9..000000000 --- a/example_configs/tmc2209_huanyang.yml +++ /dev/null @@ -1,175 +0,0 @@ -name: "TMC2209 XYZA PWM Spindle" -board: "TMC2209 4x" -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -homing_init_lock: true - -uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.25:high - - x: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - homing: - cycle: 1 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_pos_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart: - txd_pin: gpio.22 - rxd_pin: gpio.21 - baud: 115200 - mode: 8N1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.500 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.26 - direction_pin: gpio.27 - disable_pin: NO_PIN - - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.34 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm:1.00 - tmc_2209: - step_pin: gpio.33 - direction_pin: gpio.32 - addr: 1 - - motor1: - null_motor: - - z: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.39 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm:1.00 - tmc_2209: - step_pin: gpio.2 - direction_pin: gpio.14 - addr: 2 - - motor1: - null_motor: - - - a: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.36 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm:1.00 - tmc_2209: - step_pin: gpio.16 - direction_pin: gpio.15 - addr: 3 - - motor1: - null_motor: - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -probe: - pin: NO_PIN - - -Huanyang: - uart: - txd_pin: gpio.4 - rxd_pin: gpio.13 - rts_pin: gpio.17 - baud: 9600 - mode: 8N1 - modbus_id: 1 - tool_num: 0 - speed_map: 0=0% 1000=0% 24000=100% diff --git a/example_configs/tmc2209_laser.yaml b/example_configs/tmc2209_laser.yaml deleted file mode 100644 index f72dc9127..000000000 --- a/example_configs/tmc2209_laser.yaml +++ /dev/null @@ -1,242 +0,0 @@ -name: "TMC2209 XYYZ Laser" -board: "TMC2209 4x DK" -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 255 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - -uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.25:high - - x: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 1 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.35 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 1.200 - hold_amps: 0.500 - microsteps: 8 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.26 - direction_pin: gpio.27 - disable_pin: NO_PIN - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - null_motor: - - y: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.34 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 1 - r_sense_ohms: 0.110 - run_amps: 1.200 - hold_amps: 0.500 - microsteps: 8 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.33 - direction_pin: gpio.32 - disable_pin: NO_PIN - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - null_motor: - - z: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.39 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 2 - r_sense_ohms: 0.110 - run_amps: 1.200 - hold_amps: 0.500 - microsteps: 8 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.2 - direction_pin: gpio.14 - disable_pin: NO_PIN - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - null_motor: - - a: - steps_per_mm: 800.000 - max_rate_mm_per_min: 5000.000 - acceleration_mm_per_sec2: 100.000 - max_travel_mm: 300.000 - soft_limits: false - homing: - cycle: 2 - positive_direction: false - mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - seek_scaler: 1.100 - feed_scaler: 1.100 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.36 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 3 - r_sense_ohms: 0.110 - run_amps: 1.200 - hold_amps: 0.500 - microsteps: 8 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.16 - direction_pin: gpio.15 - disable_pin: NO_PIN - - motor1: - limit_neg_pin: NO_PIN - limit_pos_pin: NO_PIN - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.000 - null_motor: - - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - card_detect_pin: NO_PIN - cs_pin: gpio.5 - -probe: - pin: NO_PIN - -start: - must_home: false - -Laser: - pwm_hz: 5000 - output_pin: gpio.4 - enable_pin: gpio.12 - disable_with_s0: false - s0_with_disable: true - tool_num: 100 - speed_map: 0=0.000% 255=100.000% diff --git a/example_configs/tmc2209_relay.yaml b/example_configs/tmc2209_relay.yaml deleted file mode 100644 index 8c1f06f8b..000000000 --- a/example_configs/tmc2209_relay.yaml +++ /dev/null @@ -1,163 +0,0 @@ -name: "TMC2209 XYYZ Laser" -board: "TMC2209 4x DK" -meta: "update for 3.6.8" - -stepping: - engine: RMT - idle_ms: 250 - dir_delay_us: 1 - pulse_us: 2 - disable_delay_us: 0 - - uart1: - txd_pin: gpio.22 - rxd_pin: gpio.21 - rts_pin: NO_PIN - cts_pin: NO_PIN - baud: 115200 - mode: 8N1 - -axes: - shared_stepper_disable_pin: gpio.25:high - - x: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - homing: - cycle: 1 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_pos_pin: gpio.35 - hard_limits: false - pulloff_mm: 1.000 - tmc_2209: - uart_num: 1 - addr: 0 - r_sense_ohms: 0.110 - run_amps: 0.500 - hold_amps: 0.500 - microsteps: 32 - stallguard: 0 - stallguard_debug: false - toff_disable: 0 - toff_stealthchop: 5 - toff_coolstep: 3 - run_mode: StealthChop - homing_mode: StealthChop - use_enable: false - step_pin: gpio.26 - direction_pin: gpio.27 - disable_pin: NO_PIN - - motor1: - null_motor: - - y: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.34 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.33 - direction_pin: gpio.32 - microsteps: 16 - uart_num: 1 - addr: 1 - - motor1: - null_motor: - - z: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.39 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.2 - direction_pin: gpio.14 - uart_num: 1 - addr: 2 - - motor1: - null_motor: - - - a: - steps_per_mm: 800 - max_rate_mm_per_min: 5000 - acceleration_mm_per_sec2: 100 - max_travel_mm: 300 - - homing: - cycle: 2 - mpos_mm: 150 - positive_direction: false - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 - settle_ms: 500 - - motor0: - limit_neg_pin: NO_PIN - limit_pos_pin: gpio.36 - limit_all_pin: NO_PIN - hard_limits: false - pulloff_mm: 1.00 - tmc_2209: - step_pin: gpio.16 - direction_pin: gpio.15 - addr: 3 - - motor1: - null_motor: - -spi: - miso_pin: gpio.19 - mosi_pin: gpio.23 - sck_pin: gpio.18 - -sdcard: - cs_pin: gpio.5 - card_detect_pin: NO_PIN - -probe: - pin: NO_PIN - -Relay: - output_pin: gpio.4 diff --git a/example_configs/uartio.yaml b/example_configs/uartio.yaml new file mode 100644 index 000000000..a3425a07a --- /dev/null +++ b/example_configs/uartio.yaml @@ -0,0 +1,53 @@ +name: "UART I/O test config" +board: "6 Pack Controller" + +stepping: + engine: RMT + idle_ms: 250 + dir_delay_us: 1 + pulse_us: 2 + disable_delay_us: 0 + + +uart1: + txd_pin: gpio.4 + rxd_pin: gpio.26 + baud: 921600 + mode: 8N1 + +uart_channel1: + report_interval_ms: 75 + uart_num: 1 + all_messages: false + + +i2so: + bck_pin: gpio.22 + data_pin: gpio.21 + ws_pin: gpio.17 + +spi: + miso_pin: gpio.19 + mosi_pin: gpio.23 + sck_pin: gpio.18 + +sdcard: + cs_pin: gpio.5 + card_detect_pin: NO_PIN + +probe: + pin: NO_PIN + +user_outputs: + digital0_pin: uart_channel1.0 + digital1_pin: uart_channel1.1 + digital2_pin: uart_channel1.2 + digital3_pin: uart_channel1.3 + digital4_pin: uart_channel1.4 + digital5_pin: uart_channel1.5 + digital6_pin: uart_channel1.6 + digital7_pin: uart_channel1.7 + +coolant: + mist_pin: uart_channel1.8 + flood_pin: uart_channel1.9 diff --git a/fluidterm/fluidterm.exe b/fluidterm/fluidterm.exe index c05935ade..ceb4e5fa0 100644 Binary files a/fluidterm/fluidterm.exe and b/fluidterm/fluidterm.exe differ diff --git a/fluidterm/fluidterm.py b/fluidterm/fluidterm.py index 1a99fb98a..a6b7ac65f 100644 --- a/fluidterm/fluidterm.py +++ b/fluidterm/fluidterm.py @@ -9,6 +9,7 @@ from __future__ import absolute_import +import contextlib VERSION = 'v1.2.0' import codecs @@ -62,7 +63,7 @@ def key_description(character): # - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -class ConsoleBase(object): +class ConsoleBase: """OS abstraction for console (input/output codec, no echo)""" def __init__(self): @@ -82,12 +83,6 @@ def getkey(self): """Read a single key from the console""" return None - def write_bytes(self, byte_string): - """Write bytes (already encoded)""" - - self.byte_output.write(byte_string) - self.byte_output.flush() - def write_fluid(self, byte_string): """Write bytes (already encoded)""" self.byte_output.write(byte_string) @@ -201,10 +196,8 @@ def __init__(self): def __del__(self): ctypes.windll.kernel32.SetConsoleOutputCP(self._saved_ocp) ctypes.windll.kernel32.SetConsoleCP(self._saved_icp) - try: + with contextlib.suppress(AttributeError): ctypes.windll.kernel32.SetConsoleMode(ctypes.windll.kernel32.GetStdHandle(-11), self._saved_cm) - except AttributeError: # in case no _saved_cm - pass def getkey(self): while True: @@ -212,7 +205,7 @@ def getkey(self): if z == unichr(13): return unichr(10) elif z is unichr(0) or z is unichr(0xe0): - try: + with contextlib.suppress(KeyError): code = msvcrt.getwch() # The z value is somewhat context-dependent # When running PowerShell in its own window, @@ -221,12 +214,7 @@ def getkey(self): # with the same code value in either case. # The solution is to duplicate the navcodes values # in fncodes. - if z is unichr(0): - return self.fncodes[code] - else: - return self.navcodes[code] - except KeyError: - pass + return self.fncodes[code] if z is unichr(0) else self.navcodes[code] else: return z @@ -237,7 +225,7 @@ def cancel(self): ctypes.windll.user32.PostMessageA(hwnd, 0x100, 0x0d, 0) def clear_screen(self): - os.system('cls'); + os.system('cls') elif os.name == 'posix': import atexit @@ -246,7 +234,7 @@ def clear_screen(self): class Console(ConsoleBase): def __init__(self): - super(Console, self).__init__() + super().__init__() self.fd = sys.stdin.fileno() self.old = termios.tcgetattr(self.fd) atexit.register(self.cleanup) @@ -415,26 +403,25 @@ def rx(self, text): self.buffy = self.buffy + text.replace('\r','') retval = '' - if ('\n' in self.buffy): - rx_lines = self.buffy.split('\n') - - if (self.buffy[-1] in '\n'): # is the last character is a new line - #everything in the split is ready to be parsed - for a_line in rx_lines: + if '\n' not in self.buffy: + return '' + rx_lines = self.buffy.split('\n') + + if self.buffy[-1] in '\n': # is the last character is a new line + #everything in the split is ready to be parsed + for a_line in rx_lines: + retval = retval + self.rx_color(a_line) + '\r\n' + self.buffy = '' ## clear the buffer + retval = retval[:-2] #remove extra line end + else: + #last in the split does not have a crlf + for a_line in rx_lines: + if a_line == rx_lines[-1]: # if last in array + self.buffy = rx_lines[-1] + else: retval = retval + self.rx_color(a_line) + '\r\n' - self.buffy = '' ## clear the buffer - retval = retval[:-2] #remove extra line end - else: - #last in the split does not have a crlf - for a_line in rx_lines: - if a_line == rx_lines[-1]: # if last in array - self.buffy = rx_lines[-1] - else: - retval = retval + self.rx_color(a_line) + '\r\n' - return self.input_color + retval - else: - return '' + return self.input_color + retval def echo(self, text): @@ -446,7 +433,7 @@ def rx_color(self, text): if text[0] == '$': #colorize settings rx_lines = text.split('=') - if (len(rx_lines) == 2): + if len(rx_lines) == 2: rx_lines[0] = self.cyan_color + rx_lines[0] + self.white_color + '=' rx_lines[1] = self.yellow_color + rx_lines[1] + self.input_color return rx_lines[0] + rx_lines[1] @@ -537,6 +524,8 @@ class Miniterm(object): """ def __init__(self, serial_instance, echo=False, eol='lf', filters=()): + self.rx_transformations = None + self.tx_transformations = None self.console = Console() self.serial = serial_instance self.echo = False @@ -545,7 +534,7 @@ def __init__(self, serial_instance, echo=False, eol='lf', filters=()): self.output_encoding = 'UTF-8' self.eol = eol self.filters = ['fluidNC'] - self.update_transformations() + self.exit_character = unichr(0x1d) # GS/CTRL+] self.exit_character2 = unichr(0x11) # GS/CTRL+Q self.menu_character = unichr(0x14) # Menu: CTRL+T @@ -581,6 +570,7 @@ def start(self): self.transmitter_thread.daemon = True self.transmitter_thread.start() self.console.setup() + self.update_transformations() def stop(self): """set flag to stop worker threads""" @@ -622,16 +612,12 @@ def dump_port_settings(self): ('active' if self.serial.rts else 'inactive'), ('active' if self.serial.dtr else 'inactive'), ('active' if self.serial.break_condition else 'inactive'))) - try: + with contextlib.suppress(serial.SerialException): sys.stderr.write('--- CTS: {:8} DSR: {:8} RI: {:8} CD: {:8}\n'.format( ('active' if self.serial.cts else 'inactive'), ('active' if self.serial.dsr else 'inactive'), ('active' if self.serial.ri else 'inactive'), ('active' if self.serial.cd else 'inactive'))) - except serial.SerialException: - # on RFC 2217 ports, it can happen if no modem state notification was - # yet received. ignore this error. - pass sys.stderr.write('--- software flow control: {}\n'.format('active' if self.serial.xonxoff else 'inactive')) sys.stderr.write('--- hardware flow control: {}\n'.format('active' if self.serial.rtscts else 'inactive')) sys.stderr.write('--- serial input encoding: {}\n'.format(self.input_encoding)) @@ -641,6 +627,10 @@ def dump_port_settings(self): def reader(self): """loop and copy serial->console""" + for _ in range(5): + time.sleep(.1) + self.console.write('.') + self.console.write('\n') try: while self.alive and self._reader_alive: # read all that is there or wait for one byte @@ -653,36 +643,26 @@ def reader(self): if data: if self._xmodem_stream: self.console.write_fluid(data) - self.serial.timeout = 0.5; + self.serial.timeout = 0.5 while True: data1 = self.serial.read_until() if len(data1): self.console.write_fluid(data1) else: break - while False: # self.serial.in_waiting: - # Flush report message - ch = self.serial.read(1) - # ACK, NAK, CAN - if ch[0] == 0x06 or ch[0] == 0x15 or ch[0] == 0x18: - self._pushback = ch[0] - break - else: - self.console.write_fluid(ch) modem = XMODEM(self.getc, self.putc, mode='xmodem') if not modem.send(self._xmodem_stream, callback=self.progress): - self.console.write("XModem reception cancelled\n"); + self.console.write("XModem reception cancelled\n") modem = None self._xmodem_stream = None + elif self.raw or collecting_input_line: + self.console.write_fluid(data) else: - if self.raw or collecting_input_line: - self.console.write_fluid(data) - else: - text = self.rx_decoder.decode(data) - for transformation in self.rx_transformations: - text = transformation.rx(text) - self.console.write(text) + text = self.rx_decoder.decode(data) + for transformation in self.rx_transformations: + text = transformation.rx(text) + self.console.write(text) except serial.SerialException: self.alive = False self.console.cancel() @@ -701,7 +681,7 @@ def writer(self): # If you restart FluidNC with $bye or the reset switch, you # will have to trigger interactive mode manually time.sleep(2) # Time for FluidNC to be ready for input - self.enable_fluid_echo(); + self.enable_fluid_echo() try: while self.alive: @@ -718,7 +698,7 @@ def writer(self): self.upload_xmodem() elif c == '\x12': # CTRL+R -> reset FluidNC self.reset_fluidnc() - elif c == self.exit_character or c == self.exit_character2 or c == unichr(3): + elif c in [self.exit_character, self.exit_character2, unichr(3)]: self.stop() # exit app break else: @@ -733,11 +713,11 @@ def writer(self): except: self.alive = False raise - self.disable_fluid_echo(); + self.disable_fluid_echo() def handle_menu_key(self, c): """Implement a simple menu / settings""" - if c == self.menu_character or c == self.exit_character or c == self.exit_character2: + if c in [self.menu_character, self.exit_character, self.exit_character2]: # Menu/exit character again -> send itself self.serial.write(self.tx_encoder.encode(c)) if self.echo: @@ -747,35 +727,36 @@ def handle_menu_key(self, c): elif c == '\x15': # CTRL+U -> upload file self.upload_file() elif c in '\x08hH?': # CTRL+H, h, H, ? -> Show help + sys.stderr.write(self.get_help_text()) - elif c == '\x12': # CTRL+R -> Toggle RTS + elif c == '\x12': # CTRL+R -> Toggle RTS self.serial.rts = not self.serial.rts - sys.stderr.write('--- RTS {} ---\n'.format('active' if self.serial.rts else 'inactive')) - elif c == '\x04': # CTRL+D -> Toggle DTR + sys.stderr.write( + f"--- RTS {'active' if self.serial.rts else 'inactive'} ---\n" + ) + elif c == '\x04': # CTRL+D -> Toggle DTR self.serial.dtr = not self.serial.dtr - sys.stderr.write('--- DTR {} ---\n'.format('active' if self.serial.dtr else 'inactive')) - elif c == '\x02': # CTRL+B -> toggle BREAK condition + sys.stderr.write( + f"--- DTR {'active' if self.serial.dtr else 'inactive'} ---\n" + ) + elif c == '\x02': # CTRL+B -> toggle BREAK condition self.serial.break_condition = not self.serial.break_condition - sys.stderr.write('--- BREAK {} ---\n'.format('active' if self.serial.break_condition else 'inactive')) - elif c == '\x05': # CTRL+E -> toggle local echo + sys.stderr.write( + f"--- BREAK {'active' if self.serial.break_condition else 'inactive'} ---\n" + ) + elif c == '\x05': # CTRL+E -> toggle local echo self.echo = not self.echo - sys.stderr.write('--- local echo {} ---\n'.format('active' if self.echo else 'inactive')) + sys.stderr.write( + f"--- local echo {'active' if self.echo else 'inactive'} ---\n" + ) elif c == '\x06': # CTRL+F -> edit filters self.change_filter() - elif c == '\x0c': # CTRL+L -> EOL mode - modes = list(EOL_TRANSFORMATIONS) # keys - eol = modes.index(self.eol) + 1 - if eol >= len(modes): - eol = 0 - self.eol = modes[eol] - sys.stderr.write('--- EOL: {} ---\n'.format(self.eol.upper())) - self.update_transformations() + elif c == '\x0c': # CTRL+L -> EOL mode + self.eol_mode() elif c == '\x01': # CTRL+A -> set encoding self.change_encoding() elif c == '\x09': # CTRL+I -> info self.dump_port_settings() - #~ elif c == '\x01': # CTRL+A -> cycle escape mode - #~ elif c == '\x0c': # CTRL+L -> cycle linefeed mode elif c in 'pP': # P -> change port self.change_port() elif c in 'zZ': # S -> suspend / open port temporarily @@ -821,7 +802,16 @@ def handle_menu_key(self, c): elif c in 'qQ': self.stop() # Q -> exit app else: - sys.stderr.write('--- unknown menu character {} --\n'.format(key_description(c))) + sys.stderr.write(f'--- unknown menu character {key_description(c)} --\n') + + def eol_mode(self): + modes = list(EOL_TRANSFORMATIONS) # keys + eol = modes.index(self.eol) + 1 + if eol >= len(modes): + eol = 0 + self.eol = modes[eol] + sys.stderr.write(f'--- EOL: {self.eol.upper()} ---\n') + self.update_transformations() # Support functions for XModem file upload def getc(self, length, timeout=1): @@ -899,20 +889,20 @@ def file_dialog(self, initial): pathname = self.mac_file_dialog(initial) print(pathname) destname = self.mac_askstring(os.path.split(pathname)[1]) - return (pathname, destname) + return pathname, destname else: try: window = Tk() except: pathname = raw_input("Local file to send: ") destname = raw_input("File on FluidNC: ") - return (pathname, destname) + return pathname, destname else: pathname = filedialog.askopenfilename(title="File to Upload", initialfile=initial, filetypes=[("FluidNC Config", "*.yaml *.flnc *.txt"), ("All files", "*")]) print("path",pathname) destname = simpledialog.askstring("Uploader", "Destination Filename", initialvalue=os.path.split(pathname)[1]) window.destroy() - return (pathname, destname) + return pathname, destname def enable_fluid_echo(self): right_arrow = '\x1b[C' @@ -940,11 +930,11 @@ def upload_xmodem(self): try: self._xmodem_stream = open(filename, 'rb') #show what is happening in the console. - self.console.write('--- Sending file {} as {} ---\n'.format(filename, destname)) + self.console.write(f'--- Sending file {filename} as {destname} ---\n') #send the command to put FluidNC in receive mode self.serial.write(self.tx_encoder.encode(f'$Xmodem/Receive={destname}\n')) except IOError as e: - sys.stderr.write('--- ERROR opening file {}: {} ---\n'.format(filename, e)) + sys.stderr.write(f'--- ERROR opening file {filename}: {e} ---\n') # self._uploading = False def upload_file(self, name="config.flnc"): @@ -956,7 +946,7 @@ def upload_file(self, name="config.flnc"): if filename: try: with open(filename, 'rb') as f: - sys.stderr.write('--- Sending file {} ---\n'.format(filename)) + sys.stderr.write(f'--- Sending file {filename} ---\n') while True: block = f.read(1024) if not block: @@ -965,9 +955,9 @@ def upload_file(self, name="config.flnc"): # Wait for output buffer to drain. self.serial.flush() sys.stderr.write('.') # Progress indicator. - sys.stderr.write('\n--- File {} sent ---\n'.format(filename)) + sys.stderr.write(f'\n--- File {filename} sent ---\n') except IOError as e: - sys.stderr.write('--- ERROR opening file {}: {} ---\n'.format(filename, e)) + sys.stderr.write(f'--- ERROR opening file {filename}: {e} ---\n') # self._uploading = False def change_filter(self): @@ -976,7 +966,9 @@ def change_filter(self): sys.stderr.write('\n'.join( '--- {:<10} = {.__doc__}'.format(k, v) for k, v in sorted(TRANSFORMATIONS.items()))) - sys.stderr.write('\n--- Enter new filter name(s) [{}]: '.format(' '.join(self.filters))) + sys.stderr.write( + f"\n--- Enter new filter name(s) [{' '.join(self.filters)}]: " + ) with self.console: new_filters = sys.stdin.readline().lower().split() if new_filters: @@ -987,23 +979,23 @@ def change_filter(self): else: self.filters = new_filters self.update_transformations() - sys.stderr.write('--- filters: {}\n'.format(' '.join(self.filters))) + sys.stderr.write(f"--- filters: {' '.join(self.filters)}\n") def change_encoding(self): """change encoding on the serial port""" - sys.stderr.write('\n--- Enter new encoding name [{}]: '.format(self.input_encoding)) + sys.stderr.write(f'\n--- Enter new encoding name [{self.input_encoding}]: ') with self.console: new_encoding = sys.stdin.readline().strip() if new_encoding: try: codecs.lookup(new_encoding) except LookupError: - sys.stderr.write('--- invalid encoding name: {}\n'.format(new_encoding)) + sys.stderr.write(f'--- invalid encoding name: {new_encoding}\n') else: self.set_rx_encoding(new_encoding) self.set_tx_encoding(new_encoding) - sys.stderr.write('--- serial input encoding: {}\n'.format(self.input_encoding)) - sys.stderr.write('--- serial output encoding: {}\n'.format(self.output_encoding)) + sys.stderr.write(f'--- serial input encoding: {self.input_encoding}\n') + sys.stderr.write(f'--- serial output encoding: {self.output_encoding}\n') def change_baudrate(self): """change the baudrate""" @@ -1014,7 +1006,7 @@ def change_baudrate(self): try: self.serial.baudrate = int(sys.stdin.readline().strip()) except ValueError as e: - sys.stderr.write('--- ERROR setting baudrate: {} ---\n'.format(e)) + sys.stderr.write(f'--- ERROR setting baudrate: {e} ---\n') self.serial.baudrate = backup else: self.dump_port_settings() @@ -1345,10 +1337,8 @@ def main(default_port=None, default_baudrate=115200, default_rts=None, default_d key_description('\x12'))) miniterm.start() - try: + with contextlib.suppress(KeyboardInterrupt): miniterm.join(True) - except KeyboardInterrupt: - pass if not args.quiet: sys.stderr.write('\n--- exit ---\n') miniterm.join() diff --git a/git-version.py b/git-version.py index 4f1d9df8f..bc76b17d8 100644 --- a/git-version.py +++ b/git-version.py @@ -12,6 +12,7 @@ if gitFail: tag = "v3.0.x" rev = " (noGit)" + url = " (noGit)" else: try: tag = ( @@ -47,17 +48,24 @@ dirty = "-dirty" else: dirty = "" - rev = " (%s-%s%s)" % (branchname, revision, dirty) + url = ( + subprocess.check_output(["git", "config", "--get", "remote.origin.url"]) + .strip() + .decode("utf-8") + ) + grbl_version = tag.replace('v','').rpartition('.')[0] git_info = '%s%s' % (tag, rev) +git_url = url provisional = "FluidNC/src/version.cxx" final = "FluidNC/src/version.cpp" with open(provisional, "w") as fp: fp.write('const char* grbl_version = \"' + grbl_version + '\";\n') fp.write('const char* git_info = \"' + git_info + '\";\n') + fp.write('const char* git_url = \"' + git_url + '\";\n') if not os.path.exists(final): # No version.cpp so rename version.cxx to version.cpp diff --git a/platformio.ini b/platformio.ini index f2e0961e5..7787b9cc7 100644 --- a/platformio.ini +++ b/platformio.ini @@ -12,7 +12,7 @@ src_dir = FluidNC include_dir = FluidNC/include ; lib_dir = libraries -test_dir = FluidNC/test +test_dir = FluidNC/tests data_dir = FluidNC/data default_envs = wifi ;extra_configs=debug.ini @@ -33,7 +33,8 @@ lib_deps = bt_deps = BluetoothSerial wifi_deps = - arduinoWebSockets=https://github.com/Links2004/arduinoWebSockets + arduinoWebSockets=https://github.com/MitchBradley/arduinoWebSockets#7793f9e + WiFi=https://github.com/MitchBradley/WiFi#e63583f ; If we include the following explicit dependencies when we get the ; Arduino framework code from github, platformio picks up different ; and incompatible versions of these libraries from who knows where, @@ -157,16 +158,33 @@ extends = common_esp32_s3 lib_deps = ${common.lib_deps} ${common.bt_deps} ${common.wifi_deps} build_flags = ${common_esp32.build_flags} ${common_wifi.build_flags} ${common_bt.build_flags} -[env:native] +; This environment has bit-rot, and does not build. +; Files relevant to it reside in ./X86TestSupport and ./FluidNC/test +; TODO - Migrate tests over to [env:tests] environment +; [env:native] +; platform = native +; test_build_src = true +; build_src_filter = +; +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + +; + +; - - +; build_flags = -IX86TestSupport -std=c++17 -limagehlp +; lib_compat_mode = off +; lib_deps = +; google/googletest @ ^1.10.0 +; lib_extra_dirs = +; X86TestSupport + +[tests_common] platform = native +test_framework = googletest test_build_src = true -build_src_filter = - +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + - + - - - -build_flags = -IX86TestSupport -std=c++17 -limagehlp -lib_compat_mode = off -lib_deps = - google/googletest @ ^1.10.0 -lib_extra_dirs = - X86TestSupport +build_src_filter = + +build_flags = -std=c++17 -g + +[env:tests] +extends = tests_common +build_flags = ${tests_common.build_flags} -fsanitize=address,undefined + +[env:tests_nosan] +extends = tests_common diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 000000000..4b723d7bc --- /dev/null +++ b/requirements.txt @@ -0,0 +1 @@ +platformio == 6.1.*