diff --git a/FluidNC/esp32/StepTimer.cpp b/FluidNC/esp32/StepTimer.cpp index cf65fdf47..ed3f95a05 100644 --- a/FluidNC/esp32/StepTimer.cpp +++ b/FluidNC/esp32/StepTimer.cpp @@ -52,12 +52,15 @@ void IRAM_ATTR stepTimerStop() { void stepTimerInit(uint32_t frequency, bool (*fn)(void)) { timer_config_t config = { - .alarm_en = TIMER_ALARM_DIS, - .counter_en = TIMER_PAUSE, - .counter_dir = TIMER_COUNT_UP, - .auto_reload = TIMER_AUTORELOAD_EN, - // .clk_src = TIMER_SRC_CLK_DEFAULT, - .divider = fTimers / frequency, + alarm_en: TIMER_ALARM_DIS, + counter_en: TIMER_PAUSE, + intr_type: TIMER_INTR_LEVEL, + counter_dir: TIMER_COUNT_UP, + auto_reload: TIMER_AUTORELOAD_EN, + divider: fTimers / frequency, +# if SOC_TIMER_GROUP_SUPPORT_XTAL + clk_src: TIMER_SRC_CLK_DEFAULT, +# endif }; timer_init(TIMER_GROUP_NUM, &config); timer_set_counter_value(TIMER_GROUP_NUM, 0); diff --git a/FluidNC/src/Channel.cpp b/FluidNC/src/Channel.cpp index f31992fd6..b4c240393 100644 --- a/FluidNC/src/Channel.cpp +++ b/FluidNC/src/Channel.cpp @@ -8,71 +8,94 @@ void Channel::flushRx() { _linelen = 0; _lastWasCR = false; + while (_queue.size()) { + _queue.pop(); + } +} + +bool Channel::lineComplete(char* line, char ch) { + // The objective here is to treat any of CR, LF, or CR-LF + // as a single line ending. When we see CR, we immediately + // complete the line, setting a flag to say that the last + // character was CR. When we see LF, if the last character + // was CR, we ignore the LF because the line has already + // been completed, otherwise we complete the line. + if (ch == '\n') { + if (_lastWasCR) { + _lastWasCR = false; + return false; + } + // if (_discarding) { + // _linelen = 0; + // _discarding = false; + // return nullptr; + // } + + // Return the complete line + _line[_linelen] = '\0'; + strcpy(line, _line); + _linelen = 0; + return true; + } + _lastWasCR = ch == '\r'; + if (_lastWasCR) { + // Return the complete line + _line[_linelen] = '\0'; + strcpy(line, _line); + _linelen = 0; + return true; + } + if (ch == '\b') { + // Simple editing for interactive input - backspace erases + if (_linelen) { + --_linelen; + } + return false; + } + if (_linelen < (Channel::maxLine - 1)) { + _line[_linelen++] = ch; + } else { + // report_status_message(Error::Overflow, this); + // _linelen = 0; + // Probably should discard the rest of the line too. + // _discarding = true; + } + return false; } Channel* Channel::pollLine(char* line) { handle(); while (1) { - int ch = read(); + int ch; + if (line && _queue.size()) { + ch = _queue.front(); + _queue.pop(); + } else { + ch = read(); + } + + // ch will only be negative if read() was called and returned -1 + // The _queue path will return only nonnegative character values if (ch < 0) { break; } - if (is_realtime_command(ch)) { + if (realtimeOkay(ch) && is_realtime_command(ch)) { execute_realtime_command(static_cast(ch), *this); continue; } if (!line) { + // If we are not able to handle a line we save the character + // until later + _queue.push(uint8_t(ch)); continue; } - // The objective here is to treat any of CR, LF, or CR-LF - // as a single line ending. When we see CR, we immediately - // complete the line, setting a flag to say that the last - // character was CR. When we see LF, if the last character - // was CR, we ignore the LF because the line has already - // been completed, otherwise we complete the line. - if (ch == '\n') { - if (_lastWasCR) { - _lastWasCR = false; - continue; - } - // if (_discarding) { - // _linelen = 0; - // _discarding = false; - // return nullptr; - // } - - // Return the complete line - _line[_linelen] = '\0'; - strcpy(line, _line); - _linelen = 0; - return this; - } - _lastWasCR = ch == '\r'; - if (_lastWasCR) { - // Return the complete line - _line[_linelen] = '\0'; - strcpy(line, _line); - _linelen = 0; + if (line && lineComplete(line, ch)) { return this; } - if (ch == '\b') { - // Simple editing for interactive input - backspace erases - if (_linelen) { - --_linelen; - } - continue; - } - if (_linelen < (Channel::maxLine - 1)) { - _line[_linelen++] = ch; - } else { - // report_status_message(Error::Overflow, this); - // _linelen = 0; - // Probably should discard the rest of the line too. - // _discarding = true; - } } return nullptr; } + void Channel::ack(Error status) { switch (status) { case Error::Ok: // Error::Ok diff --git a/FluidNC/src/Channel.h b/FluidNC/src/Channel.h index 2cacd3081..e85094e74 100644 --- a/FluidNC/src/Channel.h +++ b/FluidNC/src/Channel.h @@ -18,6 +18,8 @@ #include "Error.h" // Error #include +#include +#include // TickType_T class Channel : public Stream { public: @@ -30,6 +32,8 @@ class Channel : public Stream { bool _addCR = false; char _lastWasCR = false; + std::queue _queue; + public: Channel(const char* name, bool addCR = false) : _name(name), _linelen(0), _addCR(addCR) {} virtual ~Channel() = default; @@ -38,6 +42,41 @@ class Channel : public Stream { virtual Channel* pollLine(char* line); virtual void ack(Error status); const char* name() { return _name; } - virtual int rx_buffer_available() = 0; - virtual void flushRx(); + + // 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; }; + + // flushRx() discards any characters that have already been received. It is used + // after a reset, so that anything already sent will not be processed. + virtual void flushRx(); + + // realtimeOkay() returns true if the channel can currently interpret the character as + // a Grbl realtime character. Some situations where it might return false are when + // the channel is being used for file upload or if the channel is doing line editing + // and is in the middle of an escape sequence that could include what would otherwise + // be a realtime character. + virtual bool realtimeOkay(char c) { return true; } + + // lineComplete() accumulates the character into the line, returning true if a line + // end is seen. + virtual bool lineComplete(char* line, char c); + + virtual size_t timedReadBytes(char* buffer, size_t length, TickType_t timeout) { + setTimeout(timeout); + return readBytes(buffer, length); + } + size_t timedReadBytes(uint8_t* buffer, size_t length, TickType_t timeout) { return timedReadBytes((char*)buffer, length, timeout); } + + bool setCr(bool on) { + bool retval = _addCR; + _addCR = on; + return retval; + } + + int peek() override { return -1; } + int read() override { return -1; } + int available() override { return 0; } }; diff --git a/FluidNC/src/Control.cpp b/FluidNC/src/Control.cpp index c21826737..5aac66cc0 100644 --- a/FluidNC/src/Control.cpp +++ b/FluidNC/src/Control.cpp @@ -5,47 +5,64 @@ #include "Protocol.h" // rtSafetyDoor, etc -Control::Control() : - _safetyDoor(rtSafetyDoor, "Door", 'D'), _reset(rtReset, "Reset", 'R'), _feedHold(rtFeedHold, "FeedHold", 'H'), - _cycleStart(rtCycleStart, "CycleStart", 'S'), _macro0(rtButtonMacro0, "Macro 0", '0'), _macro1(rtButtonMacro1, "Macro 1", '1'), - _macro2(rtButtonMacro2, "Macro 2", '2'), _macro3(rtButtonMacro3, "Macro 3", '3') {} +Control::Control() { + // The SafetyDoor pin must be defined first because it is checked explicity in safety_door_ajar() + _pins.push_back(new ControlPin(rtSafetyDoor, "safety_door_pin", 'D')); + _pins.push_back(new ControlPin(rtReset, "reset_pin", 'R')); + _pins.push_back(new ControlPin(rtFeedHold, "feed_hold_pin", 'H')); + _pins.push_back(new ControlPin(rtCycleStart, "cycle_start_pin", 'S')); + _pins.push_back(new ControlPin(rtButtonMacro0, "macro0_pin", '0')); + _pins.push_back(new ControlPin(rtButtonMacro1, "macro1_pin", '1')); + _pins.push_back(new ControlPin(rtButtonMacro2, "macro2_pin", '2')); + _pins.push_back(new ControlPin(rtButtonMacro3, "macro3_pin", '3')); +} void Control::init() { - _safetyDoor.init(); - _reset.init(); - _feedHold.init(); - _cycleStart.init(); - _macro0.init(); - _macro1.init(); - _macro2.init(); - _macro3.init(); + for (auto pin : _pins) { + pin->init(); + } } void Control::group(Configuration::HandlerBase& handler) { - handler.item("safety_door_pin", _safetyDoor._pin); - handler.item("reset_pin", _reset._pin); - handler.item("feed_hold_pin", _feedHold._pin); - handler.item("cycle_start_pin", _cycleStart._pin); - handler.item("macro0_pin", _macro0._pin); - handler.item("macro1_pin", _macro1._pin); - handler.item("macro2_pin", _macro2._pin); - handler.item("macro3_pin", _macro3._pin); + for (auto pin : _pins) { + handler.item(pin->_legend, pin->_pin); + } } -String Control::report() { - return _safetyDoor.report() + _reset.report() + _feedHold.report() + _cycleStart.report() + _macro0.report() + _macro1.report() + - _macro2.report() + _macro3.report(); +String Control::report_status() { + String ret = ""; + for (auto pin : _pins) { + if (pin->get()) { + ret += pin->_letter; + } + } + return ret; } bool Control::stuck() { - return _safetyDoor.get() || _reset.get() || _feedHold.get() || _cycleStart.get() || _macro0.get() || _macro1.get() || _macro2.get() || - _macro3.get(); + for (auto pin : _pins) { + if (pin->get()) { + return true; + } + } + return false; +} + +bool Control::startup_check() { + bool ret = false; + for (auto pin : _pins) { + if (pin->get()) { + log_error(pin->_legend << " is active at startup"); + ret = true; + } + } + return ret; } // Returns if safety door is ajar(T) or closed(F), based on pin state. -bool Control::system_check_safety_door_ajar() { +bool Control::safety_door_ajar() { // If a safety door pin is not defined, this will return false // because that is the default for the value field, which will // never be changed for an undefined pin. - return _safetyDoor.get(); + return _pins[0]->get(); } diff --git a/FluidNC/src/Control.h b/FluidNC/src/Control.h index 9dc523ae1..af780bf5a 100644 --- a/FluidNC/src/Control.h +++ b/FluidNC/src/Control.h @@ -5,23 +5,14 @@ #include "Configuration/Configurable.h" #include "ControlPin.h" +#include class Control : public Configuration::Configurable { -// private: - // TODO: Should we not just put this in an array so we can enumerate it easily? -public: - ControlPin _safetyDoor; - ControlPin _reset; - ControlPin _feedHold; - ControlPin _cycleStart; - ControlPin _macro0; - ControlPin _macro1; - ControlPin _macro2; - ControlPin _macro3; - public: Control(); + std::vector _pins; + // Initializes control pins. void init(); @@ -29,8 +20,10 @@ class Control : public Configuration::Configurable { void group(Configuration::HandlerBase& handler) override; bool stuck(); - bool system_check_safety_door_ajar(); - String report(); + bool safety_door_ajar(); + String report_status(); + + bool startup_check(); ~Control() = default; }; diff --git a/FluidNC/src/ControlPin.cpp b/FluidNC/src/ControlPin.cpp index adbc60203..bdb47127b 100644 --- a/FluidNC/src/ControlPin.cpp +++ b/FluidNC/src/ControlPin.cpp @@ -8,8 +8,16 @@ void IRAM_ATTR ControlPin::handleISR() { bool pinState = _pin.read(); _value = pinState; - if (pinState) { - _rtVariable = pinState; + + // Rate limit control pin events so switch bounce does not cause multiple events + if (pinState && (_debounceEnd == 0 || ((getCpuTicks() - _debounceEnd) >= 0))) { + _debounceEnd = usToEndTicks(debounceUs); + // We use 0 to mean that the debounce lockout is inactive, + // so if the end time happens to be 0, bump it up by one tick. + if (_debounceEnd == 0) { + _debounceEnd = 1; + } + _rtVariable = true; } } @@ -25,16 +33,7 @@ void ControlPin::init() { _pin.setAttr(attr); _pin.attachInterrupt(ISRHandler, CHANGE, this); _rtVariable = false; - _value = _pin.read(); - // Control pins must start in inactive state - if (_value) { - log_error(_legend << " pin is active at startup"); - rtAlarm = ExecAlarm::ControlPin; - } -} - -String ControlPin::report() { - return get() ? String(_letter) : String(""); + _value = _pin.read(); } ControlPin::~ControlPin() { diff --git a/FluidNC/src/ControlPin.h b/FluidNC/src/ControlPin.h index 5d3cf864e..e5693d651 100644 --- a/FluidNC/src/ControlPin.h +++ b/FluidNC/src/ControlPin.h @@ -6,14 +6,19 @@ class ControlPin { private: bool _value; - const char _letter; - volatile bool& _rtVariable; - const char* _legend; + volatile bool& _rtVariable; // The variable that is set when the pin is asserted + int32_t _debounceEnd = 0; void IRAM_ATTR handleISR(); CreateISRHandlerFor(ControlPin, handleISR); + // Interval during which we ignore repeated control pin activations + const int debounceUs = 10000; // 10000 us = 10 ms + public: + const char* _legend; // The name that appears in init() messages and the name of the configuration item + const char _letter; // The letter that appears in status reports when the pin is active + ControlPin(volatile bool& rtVariable, const char* legend, char letter) : _value(false), _letter(letter), _rtVariable(rtVariable), _legend(legend) { _rtVariable = _value; @@ -24,7 +29,5 @@ class ControlPin { void init(); bool get() { return _value; } - String report(); - ~ControlPin(); }; diff --git a/FluidNC/src/Custom/oled_basic.cpp b/FluidNC/src/Custom/oled_basic.cpp index ab219f902..7e2979020 100644 --- a/FluidNC/src/Custom/oled_basic.cpp +++ b/FluidNC/src/Custom/oled_basic.cpp @@ -133,27 +133,13 @@ static void oledDRO() { draw_checkbox(120, oled_y_pos + 3, 7, 7, prb_pin_state); oled_y_pos += 10; } - if (ctrl_pins->_feedHold._pin.defined()) { - oled->drawString(110, oled_y_pos, "H"); - draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_feedHold.get()); - oled_y_pos += 10; - } - if (ctrl_pins->_cycleStart._pin.defined()) { - oled->drawString(110, oled_y_pos, "S"); - draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_cycleStart.get()); - oled_y_pos += 10; - } - - if (ctrl_pins->_reset._pin.defined()) { - oled->drawString(110, oled_y_pos, "R"); - draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_reset.get()); - oled_y_pos += 10; - } - - if (ctrl_pins->_safetyDoor._pin.defined()) { - oled->drawString(110, oled_y_pos, "D"); - draw_checkbox(120, oled_y_pos + 3, 7, 7, ctrl_pins->_safetyDoor.get()); - oled_y_pos += 10; + for (auto pin : ctrl_pins->_pins) { + char letter = pin->_letter; + if (!isdigit(letter)) { + oled->drawString(110, oled_y_pos, String(letter)); + draw_checkbox(120, oled_y_pos + 3, 7, 7, pin->get()); + oled_y_pos += 10; + } } } diff --git a/FluidNC/src/FileStream.cpp b/FluidNC/src/FileStream.cpp index 5a58e3493..568cae448 100644 --- a/FluidNC/src/FileStream.cpp +++ b/FluidNC/src/FileStream.cpp @@ -27,7 +27,7 @@ int FileStream::peek() { } void FileStream::flush() {} -size_t FileStream::readBytes(char* buffer, size_t length) { +size_t FileStream::read(char* buffer, size_t length) { return fread(buffer, 1, length, _fd); } diff --git a/FluidNC/src/FileStream.h b/FluidNC/src/FileStream.h index 7c44f2e82..0dfabb2cb 100644 --- a/FluidNC/src/FileStream.h +++ b/FluidNC/src/FileStream.h @@ -30,10 +30,9 @@ class FileStream : public Channel { int read() override; int peek() override; void flush() override; - size_t readBytes(char* buffer, size_t length) override; // read chars from stream into buffer - size_t read(uint8_t* buffer, size_t length) { return readBytes((char*)buffer, length); } - int rx_buffer_available() override { return 0; } + size_t read(char* buffer, size_t length); // read chars from stream into buffer + size_t read(uint8_t* buffer, size_t length) { return read((char*)buffer, length); } size_t write(uint8_t c) override; size_t write(const uint8_t* buffer, size_t length) override; diff --git a/FluidNC/src/I2SOut.cpp b/FluidNC/src/I2SOut.cpp index 475d84c3c..3499f11e7 100644 --- a/FluidNC/src/I2SOut.cpp +++ b/FluidNC/src/I2SOut.cpp @@ -22,7 +22,27 @@ #include #include -#include +// The library routines are not in IRAM so they can crash when called from FLASH +// The GCC intrinsic versions which are prefixed with __ are compiled inline +#define USE_INLINE_ATOMIC + +#ifdef USE_INLINE_ATOMIC +# define MEMORY_MODEL_FETCH __ATOMIC_RELAXED +# define MEMORY_MODEL_STORE __ATOMIC_RELAXED +# define ATOMIC_LOAD(var) __atomic_load_n(var, MEMORY_MODEL_FETCH) +# define ATOMIC_STORE(var, val) __atomic_store_n(var, val, MEMORY_MODEL_STORE) +# define ATOMIC_FETCH_AND(var, val) __atomic_fetch_and(var, val, MEMORY_MODEL_FETCH) +# define ATOMIC_FETCH_OR(var, val) __atomic_fetch_or(var, val, MEMORY_MODEL_FETCH) +static uint32_t i2s_out_port_data = 0; +#else +# include +# define ATOMIC_LOAD(var) atomic_load(var) +# define ATOMIC_STORE(var, val) atomic_store(var, val) +# define ATOMIC_FETCH_AND(var, val) atomic_fetch_and(var, val) +# define ATOMIC_FETCH_OR(var, val) atomic_fetch_or(var, val) +static std::atomic i2s_out_port_data = ATOMIC_VAR_INIT(0); + +#endif // Make Arduino functions available extern "C" void __digitalWrite(pinnum_t pin, uint8_t val); @@ -58,9 +78,6 @@ typedef struct { static i2s_out_dma_t o_dma; static intr_handle_t i2s_out_isr_handle; -// output value -static std::atomic i2s_out_port_data = ATOMIC_VAR_INIT(0); - // inner lock static portMUX_TYPE i2s_out_spinlock = portMUX_INITIALIZER_UNLOCKED; #define I2S_OUT_ENTER_CRITICAL() \ @@ -139,7 +156,7 @@ static void IRAM_ATTR set_single_data(uint32_t portData) { void IRAM_ATTR i2s_out_push() { if (i2s_out_pulser_status == PASSTHROUGH) { - set_single_data(atomic_load(&i2s_out_port_data)); + set_single_data(ATOMIC_LOAD(&i2s_out_port_data)); } } @@ -230,7 +247,7 @@ static int i2s_out_stop() { __digitalWrite(i2s_out_bck_pin, 0); // Transmit recovery data to 74HC595 - uint32_t port_data = atomic_load(&i2s_out_port_data); // current expanded port value + uint32_t port_data = ATOMIC_LOAD(&i2s_out_port_data); // current expanded port value i2s_out_gpio_shiftout(port_data); //clear pending interrupt @@ -247,7 +264,7 @@ static int i2s_out_start() { I2S_OUT_ENTER_CRITICAL(); // Transmit recovery data to 74HC595 - uint32_t port_data = atomic_load(&i2s_out_port_data); // current expanded port value + uint32_t port_data = ATOMIC_LOAD(&i2s_out_port_data); // current expanded port value i2s_out_gpio_shiftout(port_data); // Attach I2S to specified GPIO pin @@ -348,7 +365,7 @@ static int i2s_fillout_dma_buffer(lldesc_t* dma_desc) { } } // no pulse data in push buffer (pulse off or idle or callback is not defined) - buf[o_dma.rw_pos++] = atomic_load(&i2s_out_port_data); + buf[o_dma.rw_pos++] = ATOMIC_LOAD(&i2s_out_port_data); if (i2s_out_remain_time_until_next_pulse >= I2S_OUT_USEC_PER_PULSE) { i2s_out_remain_time_until_next_pulse -= I2S_OUT_USEC_PER_PULSE; } @@ -401,7 +418,7 @@ static void IRAM_ATTR i2s_out_intr_handler(void* arg) { I2S_OUT_PULSER_ENTER_CRITICAL_ISR(); uint32_t port_data = 0; if (i2s_out_pulser_status == STEPPING) { - port_data = atomic_load(&i2s_out_port_data); + port_data = ATOMIC_LOAD(&i2s_out_port_data); } I2S_OUT_PULSER_EXIT_CRITICAL_ISR(); for (int i = 0; i < DMA_SAMPLE_COUNT; i++) { @@ -501,14 +518,14 @@ void i2s_out_delay() { void IRAM_ATTR i2s_out_write(pinnum_t pin, uint8_t val) { uint32_t bit = bitnum_to_mask(pin); if (val) { - atomic_fetch_or(&i2s_out_port_data, bit); + ATOMIC_FETCH_OR(&i2s_out_port_data, bit); } else { - atomic_fetch_and(&i2s_out_port_data, ~bit); + ATOMIC_FETCH_AND(&i2s_out_port_data, ~bit); } } uint8_t i2s_out_read(pinnum_t pin) { - uint32_t port_data = atomic_load(&i2s_out_port_data); + uint32_t port_data = ATOMIC_LOAD(&i2s_out_port_data); return (!!(port_data & bitnum_to_mask(pin))); } @@ -522,7 +539,7 @@ void IRAM_ATTR i2s_out_push_sample(uint32_t usec) { if (num == 0) { num = 1; } - uint32_t port_data = atomic_load(&i2s_out_port_data); + uint32_t port_data = ATOMIC_LOAD(&i2s_out_port_data); do { o_dma.current[o_dma.rw_pos++] = port_data; } while (--num); @@ -581,7 +598,7 @@ int i2s_out_set_stepping() { // Change I2S state from PASSTHROUGH to STEPPING i2s_out_stop(); - uint32_t port_data = atomic_load(&i2s_out_port_data); + uint32_t port_data = ATOMIC_LOAD(&i2s_out_port_data); i2s_clear_o_dma_buffers(port_data); // You need to set the status before calling i2s_out_start() @@ -601,7 +618,7 @@ int i2s_out_reset() { I2S_OUT_PULSER_ENTER_CRITICAL(); i2s_out_stop(); if (i2s_out_pulser_status == STEPPING) { - uint32_t port_data = atomic_load(&i2s_out_port_data); + uint32_t port_data = ATOMIC_LOAD(&i2s_out_port_data); i2s_clear_o_dma_buffers(port_data); } else if (i2s_out_pulser_status == WAITING) { i2s_clear_o_dma_buffers(0); @@ -624,7 +641,7 @@ int i2s_out_init(i2s_out_init_t& init_param) { return -1; } - atomic_store(&i2s_out_port_data, init_param.init_val); + ATOMIC_STORE(&i2s_out_port_data, init_param.init_val); // To make sure hardware is enabled before any hardware register operations. periph_module_reset(PERIPH_I2S0_MODULE); diff --git a/FluidNC/src/Kinematics/WallPlotter.cpp b/FluidNC/src/Kinematics/WallPlotter.cpp index 03e2cf9ca..5e06249b5 100644 --- a/FluidNC/src/Kinematics/WallPlotter.cpp +++ b/FluidNC/src/Kinematics/WallPlotter.cpp @@ -4,20 +4,6 @@ #include -/* -Default configuration - -kinematics: - WallPlotter: - left_axis: 0 - left_anchor_x: -267.000 - left_anchor_y: 250.000 - right_axis: 1 - right_anchor_x: 267.000 - right_anchor_y: 250.000 - segment_length: 10.000 -*/ - namespace Kinematics { void WallPlotter::group(Configuration::HandlerBase& handler) { handler.item("left_axis", _left_axis); @@ -37,8 +23,6 @@ namespace Kinematics { // We assume the machine starts at cartesian (0, 0, 0). // The motors assume they start from (0, 0, 0). // So we need to derive the zero lengths to satisfy the kinematic equations. - // - // TODO: Maybe we can change where the motors start, which would be simpler? xy_to_lengths(0, 0, zero_left, zero_right); last_left = zero_left; last_right = zero_right; @@ -65,49 +49,35 @@ namespace Kinematics { position = an MAX_N_AXIS array of where the machine is starting from for this move */ bool WallPlotter::cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) { - float dx, dy, dz; // distances in each cartesian axis - float p_dx, p_dy, p_dz; // distances in each polar axis + float dx, dy, dz; // segment distances in each cartesian axis uint32_t segment_count; // number of segments the move will be broken in to. - // 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]; - // calculate the total X,Y axis move distance - // Z axis is the same in both coord systems, so it is ignored + // Z axis is the same in both coord systems, so it does not undergo conversion float dist = vector_distance(target, position, Y_AXIS); - - if (pl_data->motion.rapidMotion) { - segment_count = 1; // rapid G0 motion is not used to draw, so skip the segmentation - } else { - segment_count = ceilf(dist / _segment_length); // determine the number of segments we need ... round up so there is at least 1 + // Segment our G1 and G0 moves based on yaml file. If we choose a small enough _segment_length we can hide the nonlinearity + segment_count = dist / _segment_length; + if (segment_count < 1) { // Make sure there is at least one segment, even if there is no movement + // We need to do this to make sure other things like S and M codes get updated properly by + // the planner even if there is no movement?? + segment_count = 1; } - - if (segment_count == 0 && target[Z_AXIS] != position[Z_AXIS]) { - // We are moving vertically. - last_z = target[Z_AXIS]; - - // Note that the left motor runs backward. - float cables[MAX_N_AXIS] = { 0 - (last_left - zero_left), 0 + (last_right - zero_right), last_z }; - - if (!mc_move_motors(cables, pl_data)) { - return false; - } - } - - dist /= segment_count; // segment distance + // Calc distance of individual segments + dx = (target[X_AXIS] - position[X_AXIS])/segment_count; + dy = (target[Y_AXIS] - position[Y_AXIS])/segment_count; + dz = (target[Z_AXIS] - position[Z_AXIS])/segment_count; + // Current cartesian end point of the segment + float seg_x = position[X_AXIS]; + float seg_y = position[Y_AXIS]; + float seg_z = position[Z_AXIS]; for (uint32_t segment = 1; segment <= segment_count; segment++) { - float segment_distance = float(segment_count) * segment; - // determine this segment's absolute target - float seg_x = position[X_AXIS] + (dx / segment_distance); - float seg_y = position[Y_AXIS] + (dy / segment_distance); - float seg_z = position[Z_AXIS] + (dz / segment_distance); - - float seg_left, seg_right; - // FIX: Z needs to be interpolated properly. - + // calc next cartesian end point of the next segment + seg_x += dx; + seg_y += dy; + seg_z += dz; + float seg_left, seg_right; xy_to_lengths(seg_x, seg_y, seg_left, seg_right); + // TODO: Need to adjust cartesian feedrate to motor/plotter space, just leave them alone for now #ifdef USE_CHECKED_KINEMATICS // Check the inverse computation. @@ -128,13 +98,12 @@ namespace Kinematics { last_z = seg_z; // Note that the left motor runs backward. + // TODO: It might be better to adjust motor direction in .yaml file by inverting direction pin?? float cables[MAX_N_AXIS] = { 0 - (last_left - zero_left), 0 + (last_right - zero_right), seg_z }; if (!mc_move_motors(cables, pl_data)) { return false; } } - - // TO DO don't need a feedrate for rapids return true; } @@ -147,15 +116,15 @@ namespace Kinematics { void WallPlotter::motors_to_cartesian(float* cartesian, float* motors, int n_axis) { // The motors start at zero, but effectively at zero_left, so we need to correct for the computation. // Note that the left motor runs backward. + // TODO: It might be better to adjust motor direction in .yaml file by inverting direction pin?? float absolute_x, absolute_y; lengths_to_xy((0 - motors[_left_axis]) + zero_left, (0 + motors[_right_axis]) + zero_right, absolute_x, absolute_y); - // Producing these relative coordinates. cartesian[X_AXIS] = absolute_x; cartesian[Y_AXIS] = absolute_y; cartesian[Z_AXIS] = motors[Z_AXIS]; - // Now we have a number that if fed back into the system should produce the same value. + // Now we have numbers that if fed back into the system should produce the same values. } /* @@ -198,7 +167,7 @@ namespace Kinematics { // Translate to absolute coordinates. x = _left_anchor_x + a; - y = _left_anchor_y + h; + y = _left_anchor_y - h; // flip } void WallPlotter::xy_to_lengths(float x, float y, float& left_length, float& right_length) { diff --git a/FluidNC/src/Machine/MachineConfig.cpp b/FluidNC/src/Machine/MachineConfig.cpp index 48355387e..81707ec50 100644 --- a/FluidNC/src/Machine/MachineConfig.cpp +++ b/FluidNC/src/Machine/MachineConfig.cpp @@ -160,7 +160,7 @@ namespace Machine { char* buffer = new char[filesize + 1]; buffer[filesize] = '\0'; - auto actual = file.readBytes(buffer, filesize); + auto actual = file.read(buffer, filesize); if (actual != filesize) { log_info("Configuration file:" << filename << " read error"); return false; diff --git a/FluidNC/src/Machine/Macros.h b/FluidNC/src/Machine/Macros.h index e806b374a..71ba27258 100644 --- a/FluidNC/src/Machine/Macros.h +++ b/FluidNC/src/Machine/Macros.h @@ -6,6 +6,7 @@ #include "../Configuration/Configurable.h" #include "../WebUI/InputBuffer.h" // WebUI::inputBuffer +#include "../Uart.h" namespace Machine { class Macros : public Configuration::Configurable { @@ -20,13 +21,13 @@ namespace Machine { public: Macros() = default; - void run_macro(size_t index) { + bool run_macro(size_t index) { if (index >= n_macros) { - return; + return false; } String macro = _macro[index]; if (macro == "") { - return; + return true; } // & is a proxy for newlines in macros, because you cannot @@ -35,6 +36,7 @@ namespace Machine { macro += "\n"; WebUI::inputBuffer.push(macro.c_str()); + return true; } String startup_line(size_t index) { diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 7aad21c41..f3c443031 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -30,7 +30,8 @@ extern void make_user_commands(); void setup() { try { - uartInit(); // Setup serial port + uartInit(); // Setup serial port + Uart0.println(); // create some white space after ESP32 boot info // Setup input polling loop after loading the configuration, // because the polling may depend on the config @@ -132,7 +133,6 @@ void setup() { if (!WebUI::wifi_config.begin()) { WebUI::bt_config.begin(); } - WebUI::inputBuffer.begin(); allChannels.deregistration(&startupLog); } diff --git a/FluidNC/src/Motors/Dynamixel2.cpp b/FluidNC/src/Motors/Dynamixel2.cpp index dba104188..45b042fc2 100644 --- a/FluidNC/src/Motors/Dynamixel2.cpp +++ b/FluidNC/src/Motors/Dynamixel2.cpp @@ -225,7 +225,7 @@ namespace MotorDrivers { // wait for and get the servo response uint16_t Dynamixel2::dxl_get_response(uint16_t length) { - length = _uart->readBytes(_dxl_rx_message, length, DXL_RESPONSE_WAIT_TICKS); + length = _uart->timedReadBytes((char*)_dxl_rx_message, length, DXL_RESPONSE_WAIT_TICKS); return length; } diff --git a/FluidNC/src/MyIOStream.h b/FluidNC/src/MyIOStream.h index 2f95a0290..28118e36c 100644 --- a/FluidNC/src/MyIOStream.h +++ b/FluidNC/src/MyIOStream.h @@ -4,6 +4,7 @@ #pragma once #include +#include #include "Pin.h" @@ -52,6 +53,11 @@ inline Print& operator<<(Print& lhs, const Pin& v) { return lhs; } +inline Print& operator<<(Print& lhs, IPAddress a) { + lhs.print(a.toString()); + return lhs; +} + class setprecision { int precision; diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index b889c0451..974b9b460 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -262,12 +262,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->system_check_safety_door_ajar()) { + if (config->_control->safety_door_ajar()) { rtAlarm = ExecAlarm::ControlPin; return Error::CheckDoor; } if (config->_control->stuck()) { - log_info("Control pins:" << config->_control->report()); + log_info("Control pins:" << config->_control->report_status()); rtAlarm = ExecAlarm::ControlPin; return Error::CheckControlPins; } @@ -313,7 +313,7 @@ static Error home(int cycle) { return Error::SettingDisabled; } - if (config->_control->system_check_safety_door_ajar()) { + if (config->_control->safety_door_ajar()) { return Error::CheckDoor; // Block if safety door is ajar. } @@ -596,6 +596,17 @@ static Error motors_init(const char* value, WebUI::AuthenticationLevel auth_leve return Error::Ok; } +static Error macros_run(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { + if (value) { + log_info("Running macro " << *value); + size_t macro_num = (*value) - '0'; + config->_macros->run_macro(macro_num); + return Error::Ok; + } + log_error("$Macros/Run requires a macro number argument"); + return Error::InvalidStatement; +} + static Error xmodem_receive(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { if (!value || !*value) { value = "uploaded"; @@ -604,12 +615,15 @@ static Error xmodem_receive(const char* value, WebUI::AuthenticationLevel auth_l try { outfile = new FileStream(value, "w", "/localfs"); } catch (...) { - vTaskDelay(1000); // Delay for FluidTerm to handle command echoing - Uart0.write(0x04); // Cancel xmodem transfer with EOT + delay_ms(1000); // Delay for FluidTerm to handle command echoing + out.write(0x04); // Cancel xmodem transfer with EOT log_info("Cannot open " << value); return Error::UploadFailed; } - int size = xmodemReceive(&Uart0, outfile); + bool oldCr = out.setCr(false); + delay_ms(1000); + int size = xmodemReceive(&out, outfile); + out.setCr(oldCr); if (size >= 0) { log_info("Received " << size << " bytes to file " << outfile->path()); } else { @@ -623,7 +637,7 @@ static Error xmodem_send(const char* value, WebUI::AuthenticationLevel auth_leve if (!value || !*value) { value = "config.yaml"; } - Channel* infile; + FileStream* infile; try { infile = new FileStream(value, "r"); } catch (...) { @@ -631,7 +645,7 @@ static Error xmodem_send(const char* value, WebUI::AuthenticationLevel auth_leve return Error::DownloadFailed; } log_info("Sending " << value << " via XModem"); - int size = xmodemTransmit(&Uart0, infile); + int size = xmodemTransmit(&out, infile); delete infile; if (size >= 0) { log_info("Sent " << size << " bytes"); @@ -710,6 +724,8 @@ void make_user_commands() { new UserCommand("MD", "Motor/Disable", motor_disable, notIdleOrAlarm); new UserCommand("MI", "Motors/Init", motors_init, notIdleOrAlarm); + new UserCommand("RM", "Macros/Run", macros_run, notIdleOrAlarm); + new UserCommand("HX", "Home/X", home_x, notIdleOrAlarm); new UserCommand("HY", "Home/Y", home_y, notIdleOrAlarm); new UserCommand("HZ", "Home/Z", home_z, notIdleOrAlarm); @@ -922,7 +938,6 @@ void settings_execute_startup() { } Error execute_line(char* line, Channel& channel, WebUI::AuthenticationLevel auth_level) { - Error result = Error::Ok; // Empty or comment line. For syncing purposes. if (line[0] == 0) { return Error::Ok; @@ -935,5 +950,9 @@ Error execute_line(char* line, Channel& channel, WebUI::AuthenticationLevel auth if (sys.state == State::Alarm || sys.state == State::ConfigAlarm || sys.state == State::Jog) { return Error::SystemGcLock; } - return gc_execute_line(line, channel); + Error result = gc_execute_line(line, channel); + if (result != Error::Ok) { + log_debug("Bad GCode: " << line); + } + return result; } diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 552e1a2b2..53dbda507 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -132,6 +132,9 @@ void protocol_main_loop() { report_feedback_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); @@ -139,7 +142,7 @@ void protocol_main_loop() { } else { // Check if the safety door is open. sys.state = State::Idle; - if (config->_control->system_check_safety_door_ajar()) { + if (config->_control->safety_door_ajar()) { rtSafetyDoor = true; protocol_execute_realtime(); // Enter safety door mode. Should return as IDLE state. } @@ -924,7 +927,7 @@ static void protocol_exec_rt_suspend() { } // Allows resuming from parking/safety door. Actively checks if safety door is closed and ready to resume. if (sys.state == State::SafetyDoor) { - if (!config->_control->system_check_safety_door_ajar()) { + if (!config->_control->safety_door_ajar()) { sys.suspend.bit.safetyDoorAjar = false; // Reset door ajar flag to denote ready to resume. } } diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index 4b5a76266..44410aa84 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -27,9 +27,8 @@ #include "Planner.h" // plan_get_block_buffer_available #include "Stepper.h" // step_count #include "Platform.h" // WEAK_LINK -#include "WebUI/NotificationsService.h" // WebUI::notificationsservice +#include "WebUI/NotificationsService.h" // WebUI::notificationsService #include "WebUI/WifiConfig.h" // wifi_config -#include "WebUI/TelnetServer.h" // WebUI::telnet_server #include "WebUI/BTConfig.h" // bt_config #include "WebUI/WebSettings.h" #include "InputFile.h" @@ -47,7 +46,7 @@ EspClass esp; portMUX_TYPE mmux = portMUX_INITIALIZER_UNLOCKED; void _notify(const char* title, const char* msg) { - WebUI::notificationsservice.sendMSG(title, msg); + WebUI::notificationsService.sendMSG(title, msg); } void _notifyf(const char* title, const char* format, ...) { @@ -172,24 +171,72 @@ void report_feedback_message(Message message) { // ok to send to all channels } #include "Uart.h" -// Welcome message -void report_init_message(Print& channel) { - channel << "\r\nGrbl " << grbl_version << " [FluidNC " << git_info << " ("; +const char* radio = #if defined(ENABLE_WIFI) || defined(ENABLE_BLUETOOTH) # ifdef ENABLE_WIFI - channel << "wifi"; + "wifi"; # endif - # ifdef ENABLE_BLUETOOTH - channel << "bt"; +"bt"; # endif #else - channel << "noradio"; + "noradio"; #endif +// Welcome message +void report_init_message(Print& channel) { + channel << '\n'; + const char* p = start_message->get(); + char c; + while ((c = *p++) != '\0') { + if (c == '\\') { + switch ((c = *p++)) { + case '\0': + --p; // Unconsume the null character + break; + case 'H': + channel << "'$' for help"; + break; + case 'B': + channel << git_info; + break; + case 'V': + channel << grbl_version; + break; + case 'R': + channel << radio; + break; + default: + channel << c; + break; + } + } else { + channel << c; + } + } + channel << '\n'; +} + +#if 0 +void report_init_message(Print& channel) { + channel << "\r\nGrbl " << grbl_version << " [FluidNC " << git_info << " ("; + +# if defined(ENABLE_WIFI) || defined(ENABLE_BLUETOOTH) +# ifdef ENABLE_WIFI + channel << "wifi"; +# endif + +# ifdef ENABLE_BLUETOOTH + channel << "bt"; +# endif +# else + channel << "noradio"; +# endif + channel << ") '$' for help]\n"; } +#endif // Prints current probe parameters. Upon a probe command, these parameters are updated upon a // successful probe or upon a failed probe with the G38.3 without errors command (if supported). @@ -516,7 +563,7 @@ static void pinString(Print& channel) { } } - String ctrl_pin_report = config->_control->report(); + String ctrl_pin_report = config->_control->report_status(); if (ctrl_pin_report.length()) { if (prefixNeeded) { prefixNeeded = false; diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index 1b34e2a1e..d4132d4c7 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -184,6 +184,18 @@ void execute_realtime_command(Cmd command, Channel& channel) { case Cmd::CoolantMistOvrToggle: rtAccessoryOverride.bit.coolantMistOvrToggle = 1; break; + case Cmd::Macro0: + rtButtonMacro0 = true; + break; + case Cmd::Macro1: + rtButtonMacro1 = true; + break; + case Cmd::Macro2: + rtButtonMacro2 = true; + break; + case Cmd::Macro3: + rtButtonMacro3 = true; + break; } } @@ -275,8 +287,8 @@ Channel* pollChannels(char* line) { Channel* retval = allChannels.pollLine(line); - WebUI::COMMANDS::handle(); // Handles feeding watchdog and ESP restart - WebUI::wifi_services.handle(); // OTA, web_server, telnet_server polling + WebUI::COMMANDS::handle(); // Handles ESP restart + WebUI::wifi_services.handle(); // OTA, webServer, telnetServer polling return retval; } diff --git a/FluidNC/src/Serial.h b/FluidNC/src/Serial.h index 28373c11e..6c9843920 100644 --- a/FluidNC/src/Serial.h +++ b/FluidNC/src/Serial.h @@ -38,6 +38,10 @@ enum class Cmd : uint8_t { 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, @@ -75,16 +79,8 @@ class AllChannels : public Channel { size_t write(uint8_t data) override; size_t write(const uint8_t* buffer, size_t length) override; - // Stub implementations to satisfy Stream requirements - int available() override { return 0; } - int read() { return -1; } - int peek() { return -1; } void flushRx(); - // All channels cannot be a direct command source so - // its rx_buffer_available() method should not be called. - int rx_buffer_available() override { return 0; } - String info(); Channel* pollLine(char* line) override; diff --git a/FluidNC/src/SettingsDefinitions.cpp b/FluidNC/src/SettingsDefinitions.cpp index 10b7f689e..fb4775f97 100644 --- a/FluidNC/src/SettingsDefinitions.cpp +++ b/FluidNC/src/SettingsDefinitions.cpp @@ -5,6 +5,8 @@ StringSetting* config_filename; StringSetting* build_info; +StringSetting* start_message; + IntSetting* status_mask; EnumSetting* message_level; @@ -53,4 +55,7 @@ void make_settings() { status_mask = new IntSetting("What to include in status report", GRBL, WG, "10", "Report/Status", 1, 0, 3, NULL); build_info = new StringSetting("OEM build info for $I command", EXTENDED, WG, NULL, "Firmware/Build", "", 0, 20, NULL); + + start_message = + new StringSetting("Message issued at startup", EXTENDED, WG, NULL, "Start/Message", "Grbl \\V [FluidNC \\B (\\R) \\H]", 0, 40, NULL); } diff --git a/FluidNC/src/SettingsDefinitions.h b/FluidNC/src/SettingsDefinitions.h index 9b6ed9107..772658f1c 100644 --- a/FluidNC/src/SettingsDefinitions.h +++ b/FluidNC/src/SettingsDefinitions.h @@ -6,6 +6,8 @@ extern StringSetting* config_filename; extern StringSetting* build_info; +extern StringSetting* start_message; + extern IntSetting* status_mask; extern EnumSetting* message_level; diff --git a/FluidNC/src/Spindles/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index 88214c32d..4ffb6a6b6 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -179,7 +179,7 @@ namespace Spindles { // Read the response size_t read_length = 0; - size_t current_read = uart.readBytes(rx_message, next_cmd.rx_length, response_ticks); + size_t current_read = uart.timedReadBytes(rx_message, next_cmd.rx_length, response_ticks); read_length += current_read; // Apparently some Huanyang report modbus errors in the correct way, and the rest not. Sigh. @@ -190,7 +190,7 @@ namespace Spindles { while (read_length < next_cmd.rx_length && current_read > 0) { // Try to read more; we're not there yet... - current_read = uart.readBytes(rx_message + read_length, next_cmd.rx_length - read_length, response_ticks); + current_read = uart.timedReadBytes(rx_message + read_length, next_cmd.rx_length - read_length, response_ticks); read_length += current_read; } diff --git a/FluidNC/src/StartupLog.h b/FluidNC/src/StartupLog.h index c49ec0681..801f94b8c 100644 --- a/FluidNC/src/StartupLog.h +++ b/FluidNC/src/StartupLog.h @@ -16,15 +16,7 @@ class StartupLog : public Channel { StartupLog(const char* name) : Channel(name) {} virtual ~StartupLog(); - int available(void) override { return 0; } - int read(void) override { return -1; } - size_t readBytes(char* buffer, size_t length) override { return 0; }; - int peek(void) override { return -1; } size_t write(uint8_t data) override; - - Channel* pollLine(char* line) override { return nullptr; } - - int rx_buffer_available() { return 0; } String messages(); }; diff --git a/FluidNC/src/Uart.cpp b/FluidNC/src/Uart.cpp index fee883cd0..0d65aa66a 100644 --- a/FluidNC/src/Uart.cpp +++ b/FluidNC/src/Uart.cpp @@ -8,18 +8,9 @@ #include "Logging.h" #include "Uart.h" -#include -#include -#include -#include -#include -#include #include -#include // GPIO_NUM_1 etc -#include "lineedit.h" - -Uart::Uart(int uart_num, bool addCR) : Channel("uart", addCR), _pushback(-1) { +Uart::Uart(int uart_num, bool addCR) : Channel("uart", addCR) { // Auto-assign Uart harware engine numbers; the pins will be // assigned to the engines separately static int currentNumber = 1; @@ -45,7 +36,6 @@ void Uart::begin(unsigned long baudrate) { } begin(baudrate, dataBits, stopBits, parity); - // Hmm.. TODO FIXME: if (uart_param_config(_uart_num, &conf) != ESP_OK) { ... } -> should assert?! } // Use the configured baud rate @@ -63,6 +53,7 @@ void Uart::begin(unsigned long baudrate, UartData dataBits, UartStop stopBits, U conf.flow_ctrl = UART_HW_FLOWCTRL_DISABLE; conf.rx_flow_ctrl_thresh = 0; if (uart_param_config(_uart_num, &conf) != ESP_OK) { + // TODO FIXME - should this throw an error? return; }; uart_driver_install(_uart_num, 256, 0, 0, NULL, 0); @@ -71,16 +62,23 @@ void Uart::begin(unsigned long baudrate, UartData dataBits, UartStop stopBits, U int Uart::available() { size_t size = 0; uart_get_buffered_data_len(_uart_num, &size); - return size + (_pushback >= 0); + return size + (_pushback != -1); } int Uart::peek() { - _pushback = read(); - return _pushback; + if (_pushback != -1) { + return _pushback; + } + int ch = read(); + if (ch == -1) { + return -1; + } + _pushback = ch; + return ch; } int Uart::read(TickType_t timeout) { - if (_pushback >= 0) { + if (_pushback != -1) { int ret = _pushback; _pushback = -1; return ret; @@ -89,6 +87,7 @@ int Uart::read(TickType_t timeout) { int res = uart_read_bytes(_uart_num, &c, 1, timeout); return res == 1 ? c : -1; } + int Uart::read() { return read(0); } @@ -97,61 +96,44 @@ int Uart::rx_buffer_available() { return UART_FIFO_LEN - available(); } +bool Uart::realtimeOkay(char c) { + return _lineedit->realtime(c); +} + +bool Uart::lineComplete(char* line, char c) { + if (_lineedit->step(c)) { + _linelen = _lineedit->finish(); + _line[_linelen] = '\0'; + strcpy(line, _line); + _linelen = 0; + return true; + } + return false; +} + Channel* Uart::pollLine(char* line) { - // For now we only allow UART0 to be a channel input device + // UART0 is the only Uart instance that can be a channel input device // Other UART users like RS485 use it as a dumb character device if (_lineedit == nullptr) { return nullptr; } - while (1) { - int ch; - if (line && _queue.size()) { - ch = _queue.front(); - _queue.pop(); - } else { - ch = read(); - } - - // ch will only be negative if read() was called and returned -1 - // The _queue path will return only nonnegative character values - if (ch < 0) { - break; - } - if (_lineedit->realtime(ch) && is_realtime_command(ch)) { - execute_realtime_command(static_cast(ch), *this); - continue; - } - if (line) { - if (_lineedit->step(ch)) { - _linelen = _lineedit->finish(); - _line[_linelen] = '\0'; - strcpy(line, _line); - _linelen = 0; - return this; - } - } else { - // If we are not able to handle a line we save the character - // until later - _queue.push(uint8_t(ch)); - } - } - return nullptr; + return Channel::pollLine(line); } -size_t Uart::readBytes(char* buffer, size_t length, TickType_t timeout) { - bool pushback = _pushback >= 0; - if (pushback && length) { - *buffer++ = _pushback; - _pushback = -1; - --length; +size_t Uart::timedReadBytes(char* buffer, size_t length, TickType_t timeout) { + // It is likely that _queue will be empty because timedReadBytes() is only + // used in situations where the UART is not receiving GCode commands + // and Grbl realtime characters. + size_t remlen = length; + while (remlen && _queue.size()) { + *buffer++ = _queue.front(); + _queue.pop(); } - int res = uart_read_bytes(_uart_num, (uint8_t*)buffer, length, timeout); - // The Stream class version of readBytes never returns -1, - // so if uart_read_bytes returns -1, we change that to 0 - return pushback + (res >= 0 ? res : 0); -} -size_t Uart::readBytes(char* buffer, size_t length) { - return readBytes(buffer, length, (TickType_t)0); + + int res = uart_read_bytes(_uart_num, (uint8_t*)buffer, remlen, timeout); + // If res < 0, no bytes were read + remlen -= (res < 0) ? 0 : res; + return length - remlen; } size_t Uart::write(uint8_t c) { return uart_write_bytes(_uart_num, (char*)&c, 1); @@ -203,9 +185,8 @@ bool Uart::flushTxTimed(TickType_t ticks) { Uart Uart0(0, true); // Primary serial channel with LF to CRLF conversion void uartInit() { - Uart0.setPins(GPIO_NUM_1, GPIO_NUM_3); // Tx 1, Rx 3 - standard hardware pins + // Uart0.setPins(GPIO_NUM_1, GPIO_NUM_3); // Tx 1, Rx 3 - standard hardware pins Uart0.begin(BAUD_RATE, UartData::Bits8, UartStop::Bits1, UartParity::None); - Uart0.println(); // create some white space after ESP32 boot info } void Uart::config_message(const char* prefix, const char* usage) { @@ -213,10 +194,7 @@ void Uart::config_message(const char* prefix, const char* usage) { } void Uart::flushRx() { - uart_flush_input(_uart_num); _pushback = -1; - while (_queue.size()) { - _queue.pop(); - } + uart_flush_input(_uart_num); Channel::flushRx(); } diff --git a/FluidNC/src/Uart.h b/FluidNC/src/Uart.h index 24e9d17cf..1ace5fcda 100644 --- a/FluidNC/src/Uart.h +++ b/FluidNC/src/Uart.h @@ -11,14 +11,18 @@ #include "lineedit.h" #include "Channel.h" #include // TickType_T -#include class Uart : public Channel, public Configuration::Configurable { private: - uart_port_t _uart_num; - int _pushback; - std::queue _queue; - Lineedit* _lineedit; + uart_port_t _uart_num; + Lineedit* _lineedit; + + // One character of pushback for implementing peek(). + // We cannot use the queue for this because the queue + // is after the check for realtime characters, whereas + // peek() deals with characters before realtime ones + // are handled. + int _pushback = -1; public: // These are public so that validators from classes @@ -45,11 +49,8 @@ class Uart : public Channel, public Configuration::Configurable { int available(void) override; int read(void) override; int read(TickType_t timeout); - size_t readBytes(char* buffer, size_t length, TickType_t timeout); - size_t readBytes(uint8_t* buffer, size_t length, TickType_t timeout) { - return readBytes(reinterpret_cast(buffer), length, timeout); - } - size_t readBytes(char* buffer, size_t length) override; + size_t timedReadBytes(char* buffer, size_t length, TickType_t timeout) override; + size_t timedReadBytes(uint8_t* buffer, size_t length, TickType_t timeout) { return timedReadBytes((char*)buffer, length, timeout); }; int peek(void) override; size_t write(uint8_t data) override; size_t write(const uint8_t* buffer, size_t length) override; @@ -58,11 +59,8 @@ class Uart : public Channel, public Configuration::Configurable { void flushRx() override; bool flushTxTimed(TickType_t ticks); - bool setCr(bool on) { - bool retval = _addCR; - _addCR = on; - return retval; - } + bool realtimeOkay(char c) override; + bool lineComplete(char* line, char c) override; Channel* pollLine(char* line) override; diff --git a/FluidNC/src/WebUI/BTConfig.cpp b/FluidNC/src/WebUI/BTConfig.cpp index 53888a0e3..8c52ef21e 100644 --- a/FluidNC/src/WebUI/BTConfig.cpp +++ b/FluidNC/src/WebUI/BTConfig.cpp @@ -122,6 +122,32 @@ namespace WebUI { return str; } + int BTChannel::available() { return SerialBT.available(); } + int BTChannel::read() { return SerialBT.read(); } + int BTChannel::peek() { return SerialBT.peek(); } + + bool BTChannel::realtimeOkay(char c) { return _lineedit->realtime(c); } + + bool BTChannel::lineComplete(char* line, char c) { + if (_lineedit->step(c)) { + _linelen = _lineedit->finish(); + _line[_linelen] = '\0'; + strcpy(line, _line); + _linelen = 0; + return true; + } + return false; + } + + Channel* BTChannel::pollLine(char* line) { + // UART0 is the only Uart instance that can be a channel input device + // Other UART users like RS485 use it as a dumb character device + if (_lineedit == nullptr) { + return nullptr; + } + return Channel::pollLine(line); + } + /** * begin WiFi setup */ @@ -173,10 +199,7 @@ namespace WebUI { /** * Handle not critical actions that must be done in sync environement */ - void BTConfig::handle() { - //If needed - COMMANDS::wait(0); - } + void BTConfig::handle() {} BTConfig::~BTConfig() { end(); } } diff --git a/FluidNC/src/WebUI/BTConfig.h b/FluidNC/src/WebUI/BTConfig.h index 6bd6c4873..9d7fba8cb 100644 --- a/FluidNC/src/WebUI/BTConfig.h +++ b/FluidNC/src/WebUI/BTConfig.h @@ -20,6 +20,7 @@ namespace WebUI { # include "../Configuration/Configurable.h" # include "../Config.h" // ENABLE_* # include "../Settings.h" // ENABLE_* +# include "../lineedit.h" # include # include @@ -34,18 +35,25 @@ namespace WebUI { class BTChannel : public Channel { private: + Lineedit* _lineedit; + public: // BTChannel(bool addCR = false) : _linelen(0), _addCR(addCR) {} - BTChannel() : Channel("bluetooth", true) {} + BTChannel() : Channel("bluetooth", true) { _lineedit = new Lineedit(this, _line, Channel::maxLine - 1); } virtual ~BTChannel() = default; - int available() override { return SerialBT.available(); } - int read() override { return SerialBT.read(); } - int peek() override { return SerialBT.peek(); } + int available() override; + int read() override; + int peek() override; void flush() override { SerialBT.flush(); } size_t write(uint8_t data) override; // 512 is RX_QUEUE_SIZE which is defined in BluetoothSerial.cpp but not in its .h - int rx_buffer_available() override { return 512 - available(); } + int rx_buffer_available() override { return 512 - SerialBT.available(); } + + bool realtimeOkay(char c) override; + bool lineComplete(char* line, char c) override; + + Channel* pollLine(char* line) override; }; extern BTChannel btChannel; diff --git a/FluidNC/src/WebUI/Commands.cpp b/FluidNC/src/WebUI/Commands.cpp index 92dd65f03..92c373d7b 100644 --- a/FluidNC/src/WebUI/Commands.cpp +++ b/FluidNC/src/WebUI/Commands.cpp @@ -10,30 +10,9 @@ #include #include -#ifdef __cplusplus -extern "C" { -#endif -esp_err_t esp_task_wdt_reset(); -#ifdef __cplusplus -} -#endif - namespace WebUI { bool COMMANDS::_restart_MCU = false; - /* - * delay is to avoid with asyncwebserver and may need to wait sometimes - */ - void COMMANDS::wait(uint32_t milliseconds) { - esp_task_wdt_reset(); - if (milliseconds) { - uint32_t start_time = millis(); - //wait feeding WDT - while ((millis() - start_time) < milliseconds) { - esp_task_wdt_reset(); - }; - } - } bool COMMANDS::isLocalPasswordValid(char* password) { if (!password) { return true; @@ -63,8 +42,6 @@ namespace WebUI { * Handle not critical actions that must be done in sync environement */ void COMMANDS::handle() { - COMMANDS::wait(0); - //in case of restart requested if (_restart_MCU) { ESP.restart(); while (1) {} diff --git a/FluidNC/src/WebUI/Commands.h b/FluidNC/src/WebUI/Commands.h index 0e07d88bd..9bdb85b8d 100644 --- a/FluidNC/src/WebUI/Commands.h +++ b/FluidNC/src/WebUI/Commands.h @@ -7,7 +7,6 @@ namespace WebUI { class COMMANDS { public: - static void wait(uint32_t milliseconds); static void handle(); static void restart_MCU(); static bool isLocalPasswordValid(char* password); diff --git a/FluidNC/src/WebUI/InputBuffer.cpp b/FluidNC/src/WebUI/InputBuffer.cpp index 9ccd42073..b449644e0 100644 --- a/FluidNC/src/WebUI/InputBuffer.cpp +++ b/FluidNC/src/WebUI/InputBuffer.cpp @@ -7,70 +7,21 @@ namespace WebUI { InputBuffer inputBuffer; - InputBuffer::InputBuffer() : Channel("macros"), _RXbufferSize(0), _RXbufferpos(0) {} - - void InputBuffer::begin() { - _RXbufferSize = 0; - _RXbufferpos = 0; - } - - void InputBuffer::flushRx() { - begin(); - Channel::flushRx(); - } - - void InputBuffer::end() { begin(); } + InputBuffer::InputBuffer() : Channel("macros") {} InputBuffer::operator bool() const { return true; } - int InputBuffer::available() { return _RXbufferSize; } - - int InputBuffer::availableforwrite() { return 0; } - - int InputBuffer::peek(void) { - if (_RXbufferSize > 0) { - return _RXbuffer[_RXbufferpos]; - } else { - return -1; - } - } bool InputBuffer::push(const char* data) { - int data_size = strlen(data); - if ((data_size + _RXbufferSize) <= RXBUFFERSIZE) { - int current = _RXbufferpos + _RXbufferSize; - if (current > RXBUFFERSIZE) { - current = current - RXBUFFERSIZE; - } - for (int i = 0; i < data_size; i++) { - if (current > (RXBUFFERSIZE - 1)) { - current = 0; - } - _RXbuffer[current] = data[i]; - current++; - } - _RXbufferSize += strlen(data); - return true; + char c; + while ((c = *data++) != '\0') { + _queue.push(c); } - return false; + return true; } bool InputBuffer::push(char data) { char buf[2] = { data, '\0' }; return push(buf); } - int InputBuffer::read(void) { - if (_RXbufferSize > 0) { - int v = _RXbuffer[_RXbufferpos]; - _RXbufferpos++; - if (_RXbufferpos > (RXBUFFERSIZE - 1)) { - _RXbufferpos = 0; - } - _RXbufferSize--; - return v; - } else { - return -1; - } - } - - InputBuffer::~InputBuffer() { begin(); } + InputBuffer::~InputBuffer() {} } diff --git a/FluidNC/src/WebUI/InputBuffer.h b/FluidNC/src/WebUI/InputBuffer.h index 7f8fcf3ab..299e21f36 100644 --- a/FluidNC/src/WebUI/InputBuffer.h +++ b/FluidNC/src/WebUI/InputBuffer.h @@ -11,28 +11,13 @@ namespace WebUI { InputBuffer(); size_t write(uint8_t c) override { return 0; } - void begin(); - void end(); - int available(); - int availableforwrite(); - int peek(void); - int read(void); + int availableforwrite() { return 0; }; bool push(const char* data); bool push(char data); - void flushRx(void) override; - - int rx_buffer_available() { return RXBUFFERSIZE - available(); } operator bool() const; ~InputBuffer(); - - private: - static const int RXBUFFERSIZE = 256; - - uint8_t _RXbuffer[RXBUFFERSIZE]; - uint16_t _RXbufferSize; - uint16_t _RXbufferpos; }; extern InputBuffer inputBuffer; diff --git a/FluidNC/src/WebUI/NotificationsService.cpp b/FluidNC/src/WebUI/NotificationsService.cpp index 30dcb5da0..87dc4882c 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; } #ifdef ENABLE_WIFI @@ -91,7 +91,7 @@ namespace WebUI { out << "Invalid message!" << '\n'; return Error::InvalidValue; } - if (!notificationsservice.sendMSG("GRBL Notification", parameter)) { + if (!notificationsService.sendMSG("GRBL Notification", parameter)) { out << "Cannot send message!" << '\n'; return Error::MessageFailed; } @@ -142,7 +142,7 @@ namespace WebUI { if ((answer.indexOf(linetrigger) != -1) || (strlen(linetrigger) == 0)) { break; } - COMMANDS::wait(10); + delay_ms(10); } if (strlen(expected_answer) == 0) { log_d("Answer ignored as requested"); diff --git a/FluidNC/src/WebUI/NotificationsService.h b/FluidNC/src/WebUI/NotificationsService.h index 22b59c708..029796f60 100644 --- a/FluidNC/src/WebUI/NotificationsService.h +++ b/FluidNC/src/WebUI/NotificationsService.h @@ -12,7 +12,7 @@ namespace WebUI { NotificationsService() = default; bool sendMSG(const char* title, const char* message) { return false; }; }; - extern NotificationsService notificationsservice; + extern NotificationsService notificationsService; } #else # include @@ -49,7 +49,7 @@ namespace WebUI { bool getEmailFromSettings(); }; - extern NotificationsService notificationsservice; + extern NotificationsService notificationsService; } #endif diff --git a/FluidNC/src/WebUI/Serial2Socket.cpp b/FluidNC/src/WebUI/Serial2Socket.cpp index 3233fdfd9..e7efd0264 100644 --- a/FluidNC/src/WebUI/Serial2Socket.cpp +++ b/FluidNC/src/WebUI/Serial2Socket.cpp @@ -4,7 +4,7 @@ #include "Serial2Socket.h" namespace WebUI { - Serial_2_Socket Serial2Socket; + Serial_2_Socket serial2Socket; } #ifdef ENABLE_WIFI @@ -15,19 +15,9 @@ namespace WebUI { namespace WebUI { Serial_2_Socket::Serial_2_Socket() : Channel("websocket"), _web_socket(nullptr), _TXbufferSize(0), _RXbufferSize(0), _RXbufferpos(0) {} - void Serial_2_Socket::begin(long speed) { - _TXbufferSize = 0; - _RXbufferSize = 0; - _RXbufferpos = 0; - } + void Serial_2_Socket::begin(long speed) { _TXbufferSize = 0; } - void Serial_2_Socket::end() { - _TXbufferSize = 0; - _RXbufferSize = 0; - _RXbufferpos = 0; - } - - long Serial_2_Socket::baudRate() { return 0; } + void Serial_2_Socket::end() { _TXbufferSize = 0; } bool Serial_2_Socket::attachWS(WebSocketsServer* web_socket) { if (web_socket) { @@ -45,8 +35,6 @@ namespace WebUI { Serial_2_Socket::operator bool() const { return true; } - int Serial_2_Socket::available() { return _RXbufferSize; } - size_t Serial_2_Socket::write(uint8_t c) { if (!_web_socket) { return 0; @@ -56,13 +44,12 @@ namespace WebUI { } size_t Serial_2_Socket::write(const uint8_t* buffer, size_t size) { - if ((buffer == NULL) || (!_web_socket)) { - if (buffer == NULL) { - log_i("[SOCKET]No buffer"); - } - if (!_web_socket) { - log_i("[SOCKET]No socket"); - } + if (buffer == NULL) { + log_i("[SOCKET]No buffer"); + return 0; + } + if (!_web_socket) { + log_i("[SOCKET]No socket"); return 0; } @@ -78,58 +65,21 @@ namespace WebUI { _TXbufferSize++; } log_i("[SOCKET]buffer size %d", _TXbufferSize); - handle_flush(); + handle(); return size; } - int Serial_2_Socket::peek(void) { - if (_RXbufferSize > 0) { - return _RXbuffer[_RXbufferpos]; - } else { - return -1; - } - } - bool Serial_2_Socket::push(const uint8_t* data, size_t length) { - if ((length + _RXbufferSize) <= RXBUFFERSIZE) { - int current = _RXbufferpos + _RXbufferSize; - if (current > RXBUFFERSIZE) { - current = current - RXBUFFERSIZE; - } - - for (int i = 0; i < length; i++) { - if (current > (RXBUFFERSIZE - 1)) { - current = 0; - } - _RXbuffer[current] = data[i]; - current++; - } - - _RXbufferSize += length; - return true; + char c; + while ((c = *data++) != '\0') { + _queue.push(c); } - return false; + return true; } bool Serial_2_Socket::push(const char* data) { return push((uint8_t*)data, strlen(data)); } - int Serial_2_Socket::read(void) { - handle_flush(); - if (_RXbufferSize > 0) { - int v = _RXbuffer[_RXbufferpos]; - _RXbufferpos++; - - if (_RXbufferpos > (RXBUFFERSIZE - 1)) { - _RXbufferpos = 0; - } - _RXbufferSize--; - return v; - } else { - return -1; - } - } - - void Serial_2_Socket::handle_flush() { + void Serial_2_Socket::handle() { if (_TXbufferSize > 0 && ((_TXbufferSize >= TXBUFFERSIZE) || ((millis() - _lastflush) > FLUSHTIMEOUT))) { log_i("[SOCKET]need flush, buffer size %d", _TXbufferSize); flush(); @@ -148,19 +98,11 @@ namespace WebUI { } } - void Serial_2_Socket::flushRx() { - _RXbufferSize = 0; - _RXbufferpos = 0; - Channel::flush(); - } - Serial_2_Socket::~Serial_2_Socket() { if (_web_socket) { detachWS(); } _TXbufferSize = 0; - _RXbufferSize = 0; - _RXbufferpos = 0; } } #endif diff --git a/FluidNC/src/WebUI/Serial2Socket.h b/FluidNC/src/WebUI/Serial2Socket.h index 655d7adb9..9892db23d 100644 --- a/FluidNC/src/WebUI/Serial2Socket.h +++ b/FluidNC/src/WebUI/Serial2Socket.h @@ -14,10 +14,9 @@ namespace WebUI { public: Serial_2_Socket() = default; int read() { return -1; } - void handle_flush() {} size_t write(const uint8_t* buffer, size_t size) { return 0; } }; - extern Serial_2_Socket Serial2Socket; + extern Serial_2_Socket serial2Socket; } #else @@ -43,21 +42,17 @@ 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); } - long baudRate(); void begin(long speed); void end(); - int available(); - int peek(void); - int read(void); + void handle(); + bool push(const uint8_t* data, size_t length); bool push(const char* data); void flush(void); - void flushRx(void) override; - void handle_flush(); bool attachWS(WebSocketsServer* web_socket); bool detachWS(); - int rx_buffer_available() { return RXBUFFERSIZE - available(); } + int rx_buffer_available() override { return RXBUFFERSIZE - available(); } operator bool() const; @@ -75,7 +70,7 @@ namespace WebUI { uint16_t _RXbufferpos; }; - extern Serial_2_Socket Serial2Socket; + extern Serial_2_Socket serial2Socket; } #endif diff --git a/FluidNC/src/WebUI/TelnetClient.cpp b/FluidNC/src/WebUI/TelnetClient.cpp new file mode 100644 index 000000000..75c5ab9ea --- /dev/null +++ b/FluidNC/src/WebUI/TelnetClient.cpp @@ -0,0 +1,88 @@ +// Copyright 2022 Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +// #include "../Machine/MachineConfig.h" +#include "TelnetClient.h" +#include "TelnetServer.h" + +#ifdef ENABLE_WIFI + +# include "WifiServices.h" + +# include + +namespace WebUI { + TelnetClient::TelnetClient(WiFiClient* wifiClient) : Channel("telnet"), _wifiClient(wifiClient) {} + + void TelnetClient::handle() {} + + void TelnetClient::closeOnDisconnect() { + if (_state != -1 && !_wifiClient->connected()) { + _state = -1; + telnetServer._disconnected.push(this); + } + } + + void TelnetClient::flushRx() { Channel::flushRx(); } + + size_t TelnetClient::write(uint8_t data) { return write(&data, 1); } + + size_t TelnetClient::write(const uint8_t* buffer, size_t length) { + // Replace \n with \r\n + size_t rem = length; + uint8_t lastchar = '\0'; + size_t j = 0; + while (rem) { + const int bufsize = 128; + uint8_t modbuf[bufsize]; + // bufsize-1 in case the last character is \n + size_t k = 0; + while (rem && k < (bufsize - 1)) { + uint8_t c = buffer[j++]; + if (c == '\n' && lastchar != '\r') { + modbuf[k++] = '\r'; + } + lastchar = c; + modbuf[k++] = c; + --rem; + } + if (k) { + auto nWritten = _wifiClient->write(modbuf, k); + if (nWritten == 0) { + closeOnDisconnect(); + } + } + } + return length; + } + + int TelnetClient::peek(void) { return _wifiClient->peek(); } + + int TelnetClient::available() { return _wifiClient->available(); } + + int TelnetClient::rx_buffer_available() { return WIFI_CLIENT_READ_BUFFER_SIZE - available(); } + + int TelnetClient::read(void) { + if (_state == -1) { + return -1; + } + auto ret = _wifiClient->read(); + if (ret < 0) { + // calling _wifiClient->connected() is expensive when the client is + // connected because it calls recv() to double check, so we check + // infrequently, only after quite a few reads have returned no data + if (++_state >= DISCONNECT_CHECK_COUNTS) { + _state = 0; + closeOnDisconnect(); // sets _state to -1 if disconnected + } + } else { + // Reset the counter if we have data + _state = 0; + } + return ret; + } + + TelnetClient::~TelnetClient() { delete _wifiClient; } +} + +#endif diff --git a/FluidNC/src/WebUI/TelnetClient.h b/FluidNC/src/WebUI/TelnetClient.h new file mode 100644 index 000000000..861d84bd7 --- /dev/null +++ b/FluidNC/src/WebUI/TelnetClient.h @@ -0,0 +1,47 @@ +// Copyright (c) 2022 Mitch Bradley +// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. + +#pragma once + +#include "../Config.h" // ENABLE_* +#include "../Channel.h" + +#ifdef ENABLE_WIFI +# include + +namespace WebUI { + class TelnetClient : public Channel { + WiFiClient* _wifiClient; + + // The default value of the rx buffer in WiFiClient.cpp is 1436 which is + // related to the network frame size minus TCP/IP header sizes. + // The WiFiClient API has no way to override or query it. + // We use a smaller value for safety. There is little advantage + // to sending too many GCode lines at once, especially since the + // common serial communication case is typically limited to 128 bytes. + static const int WIFI_CLIENT_READ_BUFFER_SIZE = 1200; + + static const int DISCONNECT_CHECK_COUNTS = 1000; + + int _state = 0; + + public: + TelnetClient(WiFiClient* wifiClient); + + int rx_buffer_available() override; + size_t write(uint8_t data) override; + size_t write(const uint8_t* buffer, size_t size) override; + int read(void) override; + int peek(void) override; + int available() override; + void flush() override {} + void flushRx() override; + + void closeOnDisconnect(); + + void handle() override; + + ~TelnetClient(); + }; +} +#endif diff --git a/FluidNC/src/WebUI/TelnetServer.cpp b/FluidNC/src/WebUI/TelnetServer.cpp index 97c861067..6f559f5ec 100644 --- a/FluidNC/src/WebUI/TelnetServer.cpp +++ b/FluidNC/src/WebUI/TelnetServer.cpp @@ -2,13 +2,16 @@ // Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file. #include "../Machine/MachineConfig.h" +#include "TelnetClient.h" #include "TelnetServer.h" #include "WebSettings.h" +#include "../Uart.h" + #ifdef ENABLE_WIFI namespace WebUI { - Telnet_Server telnet_server; + TelnetServer telnetServer; } # include "WifiServices.h" @@ -20,28 +23,20 @@ namespace WebUI { # include namespace WebUI { - bool Telnet_Server::_setupdone = false; - uint16_t Telnet_Server::_port = 0; - WiFiServer* Telnet_Server::_telnetserver = NULL; - WiFiClient Telnet_Server::_telnetClients[MAX_TLNT_CLIENTS]; EnumSetting* telnet_enable; IntSetting* telnet_port; - IPAddress Telnet_Server::_telnetClientsIP[MAX_TLNT_CLIENTS]; - - Telnet_Server::Telnet_Server() : Channel("telnet"), _RXbufferSize(0), _RXbufferpos(0) { + TelnetServer::TelnetServer() { telnet_port = new IntSetting( "Telnet Port", WEBSET, WA, "ESP131", "Telnet/Port", DEFAULT_TELNETSERVER_PORT, MIN_TELNET_PORT, MAX_TELNET_PORT, NULL); telnet_enable = new EnumSetting("Telnet Enable", WEBSET, WA, "ESP130", "Telnet/Enable", DEFAULT_TELNET_STATE, &onoffOptions, NULL); } - bool Telnet_Server::begin() { + bool TelnetServer::begin() { bool no_error = true; end(); - _RXbufferSize = 0; - _RXbufferpos = 0; if (!WebUI::telnet_enable->get()) { return false; @@ -49,202 +44,48 @@ namespace WebUI { _port = WebUI::telnet_port->get(); //create instance - _telnetserver = new WiFiServer(_port, MAX_TLNT_CLIENTS); - _telnetserver->setNoDelay(true); + _wifiServer = new WiFiServer(_port, MAX_TLNT_CLIENTS); + _wifiServer->setNoDelay(true); log_info("Telnet started on port " << _port); //start telnet server - _telnetserver->begin(); + _wifiServer->begin(); _setupdone = true; - allChannels.registration(&telnet_server); return no_error; } - void Telnet_Server::flushRx() { - _RXbufferSize = 0; - _RXbufferpos = 0; - Channel::flushRx(); - } - - void Telnet_Server::end() { - _setupdone = false; - _RXbufferSize = 0; - _RXbufferpos = 0; - if (_telnetserver) { - allChannels.deregistration(&telnet_server); - delete _telnetserver; - _telnetserver = NULL; - } - } - - void Telnet_Server::clearClients() { - //check if there are any new clients - if (_telnetserver->hasClient()) { - size_t i; - for (i = 0; i < MAX_TLNT_CLIENTS; i++) { - //find free/disconnected spot - if (!_telnetClients[i] || !_telnetClients[i].connected()) { - _telnetClientsIP[i] = IPAddress(0, 0, 0, 0); - if (_telnetClients[i]) { - _telnetClients[i].stop(); - } - _telnetClients[i] = _telnetserver->available(); - break; - } - } - if (i >= MAX_TLNT_CLIENTS) { - //no free/disconnected spot so reject - _telnetserver->available().stop(); - } + void TelnetServer::end() { + _setupdone = false; + if (_wifiServer) { + // delete _wifiServer; + _wifiServer = NULL; } } - size_t Telnet_Server::write(uint8_t data) { return write(&data, 1); } - - size_t Telnet_Server::write(const uint8_t* buffer, size_t length) { - if (!_setupdone || _telnetserver == NULL) { - return 0; - } - clearClients(); - - // Replace \n with \r\n - size_t rem = length; - uint8_t lastchar = '\0'; - size_t j = 0; - while (rem) { - const int bufsize = 80; - uint8_t modbuf[bufsize]; - // bufsize-1 in case the last character is \n - size_t k = 0; - while (rem && k < (bufsize - 1)) { - uint8_t c = buffer[j++]; - if (c == '\n' && lastchar != '\r') { - modbuf[k++] = '\r'; - } - lastchar = c; - modbuf[k++] = c; - --rem; - } - - //push data to all connected telnet clients - for (size_t i = 0; i < MAX_TLNT_CLIENTS; i++) { - if (_telnetClients[i] && _telnetClients[i].connected()) { - _telnetClients[i].write(modbuf, k); - COMMANDS::wait(0); - } - } - } - return length; - } - - void Telnet_Server::handle() { - COMMANDS::wait(0); - //check if can read - if (!_setupdone || _telnetserver == NULL) { + void TelnetServer::handle() { + if (!_setupdone || _wifiServer == NULL) { return; } - clearClients(); - //check clients for data - for (size_t i = 0; i < MAX_TLNT_CLIENTS; i++) { - if (_telnetClients[i] && _telnetClients[i].connected()) { - if (_telnetClientsIP[i] != _telnetClients[i].remoteIP()) { - report_init_message(telnet_server); - _telnetClientsIP[i] = _telnetClients[i].remoteIP(); - } - if (_telnetClients[i].available()) { - uint8_t buf[1024]; - COMMANDS::wait(0); - int readlen = _telnetClients[i].available(); - int writelen = TELNETRXBUFFERSIZE - available(); - if (readlen > 1024) { - readlen = 1024; - } - if (readlen > writelen) { - readlen = writelen; - } - if (readlen > 0) { - _telnetClients[i].read(buf, readlen); - push(buf, readlen); - } - return; - } - } else { - if (_telnetClients[i]) { - _telnetClientsIP[i] = IPAddress(0, 0, 0, 0); - _telnetClients[i].stop(); - } - } - COMMANDS::wait(0); - } - } - - int Telnet_Server::peek(void) { - if (_RXbufferSize > 0) { - return _RXbuffer[_RXbufferpos]; - } else { - return -1; - } - } - int Telnet_Server::available() { return _RXbufferSize; } - - int Telnet_Server::rx_buffer_available() { return TELNETRXBUFFERSIZE - _RXbufferSize; } - - bool Telnet_Server::push(uint8_t data) { - if ((1 + _RXbufferSize) <= TELNETRXBUFFERSIZE) { - int current = _RXbufferpos + _RXbufferSize; - if (current > TELNETRXBUFFERSIZE) { - current = current - TELNETRXBUFFERSIZE; - } - if (current > (TELNETRXBUFFERSIZE - 1)) { - current = 0; - } - _RXbuffer[current] = data; - _RXbufferSize++; - return true; + while (_disconnected.size()) { + log_debug("Telnet client disconnected"); + TelnetClient* client = _disconnected.front(); + _disconnected.pop(); + allChannels.deregistration(client); + delete client; } - return false; - } - bool Telnet_Server::push(const uint8_t* data, int data_size) { - if ((data_size + _RXbufferSize) <= TELNETRXBUFFERSIZE) { - int data_processed = 0; - int current = _RXbufferpos + _RXbufferSize; - if (current > TELNETRXBUFFERSIZE) { - current = current - TELNETRXBUFFERSIZE; - } - for (int i = 0; i < data_size; i++) { - if (current > (TELNETRXBUFFERSIZE - 1)) { - current = 0; - } - - _RXbuffer[current] = data[i]; - current++; - data_processed++; - - COMMANDS::wait(0); - //vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks - } - _RXbufferSize += data_processed; - return true; - } - return false; - } - - int Telnet_Server::read(void) { - if (_RXbufferSize > 0) { - int v = _RXbuffer[_RXbufferpos]; - _RXbufferpos++; - if (_RXbufferpos > (TELNETRXBUFFERSIZE - 1)) { - _RXbufferpos = 0; + //check if there are any new clients + if (_wifiServer->hasClient()) { + WiFiClient* tcpClient = new WiFiClient(_wifiServer->available()); + if (!tcpClient) { + log_error("Creating telnet client failed"); } - _RXbufferSize--; - return v; - } else { - return -1; + log_debug("Telnet from " << tcpClient->remoteIP()); + TelnetClient* tnc = new TelnetClient(tcpClient); + allChannels.registration(tnc); } } - - Telnet_Server::~Telnet_Server() { end(); } + TelnetServer::~TelnetServer() { end(); } } #endif diff --git a/FluidNC/src/WebUI/TelnetServer.h b/FluidNC/src/WebUI/TelnetServer.h index 416d108b6..42f57f3fc 100644 --- a/FluidNC/src/WebUI/TelnetServer.h +++ b/FluidNC/src/WebUI/TelnetServer.h @@ -5,66 +5,48 @@ #include "../Config.h" // ENABLE_* #include "../Channel.h" +#include #ifdef ENABLE_WIFI # include "../Settings.h" -class WiFiServer; -class WiFiClient; +# include + +class TelnetClient; namespace WebUI { - class Telnet_Server : public Channel { + class TelnetServer { static const int DEFAULT_TELNET_STATE = 1; static const int DEFAULT_TELNETSERVER_PORT = 23; static const int MAX_TELNET_PORT = 65001; static const int MIN_TELNET_PORT = 1; - //how many clients should be able to telnet to this ESP32 - static const int MAX_TLNT_CLIENTS = 1; + static const int MAX_TLNT_CLIENTS = 2; - static const int TELNETRXBUFFERSIZE = 1200; - static const int FLUSHTIMEOUT = 500; + static const int FLUSHTIMEOUT = 500; public: - Telnet_Server(); + TelnetServer(); - bool begin(); - void end(); - void handle() override; - size_t write(uint8_t data) override; - size_t write(const uint8_t* buffer, size_t size); - int read(void); - int peek(void); - int available(); - bool push(uint8_t data); - bool push(const uint8_t* data, int datasize); - void flush() override {} - void flushRx() override; + bool begin(); + void end(); + void handle(); - int rx_buffer_available() override; + uint16_t port() { return _port; } - static uint16_t port() { return _port; } + std::queue _disconnected; - ~Telnet_Server(); + ~TelnetServer(); private: - static bool _setupdone; - static WiFiServer* _telnetserver; - static WiFiClient _telnetClients[MAX_TLNT_CLIENTS]; - static IPAddress _telnetClientsIP[MAX_TLNT_CLIENTS]; - static uint16_t _port; - - void clearClients(); - - uint32_t _lastflush; - uint8_t _RXbuffer[TELNETRXBUFFERSIZE]; - uint16_t _RXbufferSize; - uint16_t _RXbufferpos; + bool _setupdone = false; + WiFiServer* _wifiServer = nullptr; + uint16_t _port = 0; }; - extern Telnet_Server telnet_server; + extern TelnetServer telnetServer; } #endif diff --git a/FluidNC/src/WebUI/WebClient.cpp b/FluidNC/src/WebUI/WebClient.cpp index c5118e8c7..593f6f20f 100644 --- a/FluidNC/src/WebUI/WebClient.cpp +++ b/FluidNC/src/WebUI/WebClient.cpp @@ -7,11 +7,25 @@ # include namespace WebUI { - WebClient::WebClient(WebServer* webserver, bool silent) : - Channel("webclient"), _header_sent(false), _silent(silent), _webserver(webserver), _buflen(0) {} + WebClient webClient; + + WebClient::WebClient() : Channel("webclient") {} + + void WebClient::attachWS(WebServer* webserver, bool silent) { + _header_sent = false; + _silent = silent; + _webserver = webserver; + _buflen = 0; + } + + void WebClient::detachWS() { + flush(); + _webserver->sendContent(""); //close connection + _webserver = nullptr; + } size_t WebClient::write(const uint8_t* buffer, size_t length) { - if (_silent) { + if (!_webserver || _silent) { return length; } if (!_header_sent) { @@ -39,12 +53,11 @@ namespace WebUI { size_t WebClient::write(uint8_t data) { return write(&data, 1); } void WebClient::flush() { - if (_buflen) { + if (_webserver && _buflen) { _webserver->sendContent(_buffer, _buflen); _buflen = 0; } } - void WebClient::flushRx() { Channel::flushRx(); } WebClient::~WebClient() { flush(); diff --git a/FluidNC/src/WebUI/WebClient.h b/FluidNC/src/WebUI/WebClient.h index 0acdc20b9..450f338cf 100644 --- a/FluidNC/src/WebUI/WebClient.h +++ b/FluidNC/src/WebUI/WebClient.h @@ -12,31 +12,28 @@ class WebServer; namespace WebUI { class WebClient : public Channel { public: - WebClient(WebServer* webserver, bool silent); + WebClient(); ~WebClient(); + void attachWS(WebServer* webserver, bool silent); + void detachWS(); + size_t write(uint8_t data) override; size_t write(const uint8_t* buffer, size_t length) override; void flush(); bool anyOutput() { return _header_sent; } - // Stub implementations to satisfy Stream requirements - int available() override { return 0; } - int read() { return -1; } - int peek() { return -1; } - - void flushRx() override; - - int rx_buffer_available() { return BUFLEN - available(); } - private: - bool _header_sent; - bool _silent; - WebServer* _webserver; - static const size_t BUFLEN = 1200; + bool _header_sent = false; + bool _silent = false; + WebServer* _webserver = nullptr; + static const size_t BUFLEN = 1200; char _buffer[BUFLEN]; - size_t _buflen; + size_t _buflen = 0; }; + + extern WebClient webClient; } + #endif diff --git a/FluidNC/src/WebUI/WebServer.cpp b/FluidNC/src/WebUI/WebServer.cpp index 7d6685030..5ccab8038 100644 --- a/FluidNC/src/WebUI/WebServer.cpp +++ b/FluidNC/src/WebUI/WebServer.cpp @@ -66,7 +66,7 @@ namespace WebUI { const int ESP_ERROR_UPLOAD_CANCELLED = 6; const int ESP_ERROR_FILE_CLOSE = 7; - Web_Server web_server; + Web_Server webServer; bool Web_Server::_setupdone = false; uint16_t Web_Server::_port = 0; long Web_Server::_id_connection = 0; @@ -115,8 +115,8 @@ namespace WebUI { _socket_server->onEvent(handle_Websocket_Event); //Websocket output - Serial2Socket.attachWS(_socket_server); - allChannels.registration(&WebUI::Serial2Socket); + serial2Socket.attachWS(_socket_server); + allChannels.registration(&WebUI::serial2Socket); //events functions //_web_events->onConnect(handle_onevent_connect); @@ -207,7 +207,7 @@ namespace WebUI { mdns_service_remove("_http", "_tcp"); if (_socket_server) { - allChannels.deregistration(&WebUI::Serial2Socket); + allChannels.deregistration(&WebUI::serial2Socket); delete _socket_server; _socket_server = NULL; } @@ -430,11 +430,11 @@ namespace WebUI { if (ESPpos > -1) { char line[256]; strncpy(line, cmd.c_str(), 255); - WebClient* webresponse = new WebClient(_webserver, silent); - Error err = settings_execute_line(line, *webresponse, auth_level); - String answer; + webClient.attachWS(_webserver, silent); + Error err = settings_execute_line(line, webClient, auth_level); + String answer; if (err == Error::Ok) { - answer = "ok"; + answer = "ok\n"; } else { const char* msg = errorString(err); answer = "Error: "; @@ -443,41 +443,30 @@ namespace WebUI { } else { answer += static_cast(err); } + answer += "\n"; } - if (!webresponse->anyOutput()) { + if (!webClient.anyOutput()) { _webserver->send(err != Error::Ok ? 500 : 200, "text/plain", answer); } - delete webresponse; + webClient.detachWS(); } else { //execute GCODE if (auth_level == AuthenticationLevel::LEVEL_GUEST) { _webserver->send(401, "text/plain", "Authentication failed!\n"); return; } - //Instead of send several commands one by one by web / send full set and split here - String scmd; - bool hasError = false; - // TODO Settings - this is very inefficient. get_Splited_Value() is O(n^2) - // when it could easily be O(n). Also, it would be just as easy to push - // the entire string into Serial2Socket and pull off lines from there. - for (size_t sindex = 0; (scmd = get_Splited_Value(cmd, '\n', sindex)) != ""; sindex++) { + if (!silent) { // 0xC2 is an HTML encoding prefix that, in UTF-8 mode, - // precede 0x90 and 0xa0-0bf, which are GRBL realtime commands. + // precedes 0x90 and 0xa0-0bf, which are GRBL realtime commands. // There are other encodings for 0x91-0x9f, so I am not sure // how - or whether - those commands work. // Ref: https://www.w3schools.com/tags/ref_urlencode.ASP - if (!silent && (scmd.length() == 2) && (scmd[0] == 0xC2)) { - scmd[0] = scmd[1]; - scmd.remove(1, 1); - } - if (scmd.length() > 1) { - scmd += "\n"; - } else if (!is_realtime_command(scmd[0])) { - scmd += "\n"; - } - if (!Serial2Socket.push(scmd.c_str())) { - hasError = true; - } + String prefix(0xc2); + cmd.replace(prefix, ""); } + if (!(cmd.length() == 1 && is_realtime_command(cmd[0])) && !cmd.endsWith("\n")) { + cmd += '\n'; + } + bool hasError = !serial2Socket.push(cmd.c_str()); _webserver->send(200, "text/plain", hasError ? "Error" : ""); } } @@ -905,7 +894,6 @@ namespace WebUI { } } uploadCheck(upload.filename, "/localfs"); - COMMANDS::wait(0); } //Web Update handler @@ -927,7 +915,7 @@ namespace WebUI { //if success restart if (_upload_status == UploadStatus::SUCCESSFUL) { - COMMANDS::wait(1000); + delay_ms(1000); COMMANDS::restart_MCU(); } else { _upload_status = UploadStatus::NONE; @@ -1025,8 +1013,6 @@ namespace WebUI { cancelUpload(); Update.end(); } - - COMMANDS::wait(0); } //Function to delete not empty directory on SD card @@ -1063,7 +1049,6 @@ namespace WebUI { break; } } - COMMANDS::wait(0); //wdtFeed } file.close(); return result ? fs.rmdir(path) : false; @@ -1208,7 +1193,6 @@ namespace WebUI { File entry = dir.openNextFile(); int i = 0; while (entry) { - COMMANDS::wait(1); if (i > 0) { jsonfile += ","; } @@ -1432,12 +1416,10 @@ namespace WebUI { } } uploadCheck(upload.filename, "/sd"); - COMMANDS::wait(0); } void Web_Server::handle() { static uint32_t start_time = millis(); - COMMANDS::wait(0); if (WiFi.getMode() == WIFI_AP) { dnsServer.processNextRequest(); } @@ -1470,33 +1452,13 @@ namespace WebUI { } break; case WStype_TEXT: case WStype_BIN: - Serial2Socket.push(payload, length); + serial2Socket.push(payload, length); break; default: break; } } - // The separator that is passed in to this function is always '\n' - // The string that is returned does not contain the separator - // The calling code adds back the separator, unless the string is - // a one-character realtime command. - String Web_Server::get_Splited_Value(String data, char separator, int index) { - int found = 0; - int strIndex[] = { 0, -1 }; - int maxIndex = data.length() - 1; - - for (int i = 0; i <= maxIndex && found <= index; i++) { - if (data.charAt(i) == separator || i == maxIndex) { - found++; - strIndex[0] = strIndex[1] + 1; - strIndex[1] = (i == maxIndex) ? i + 1 : i; - } - } - - return found > index ? data.substring(strIndex[0], strIndex[1]) : ""; - } - //helper to extract content type from file extension //Check what is the content tye according extension file String Web_Server::getContentType(String filename) { diff --git a/FluidNC/src/WebUI/WebServer.h b/FluidNC/src/WebUI/WebServer.h index 2bbf7ce12..b95ca6673 100644 --- a/FluidNC/src/WebUI/WebServer.h +++ b/FluidNC/src/WebUI/WebServer.h @@ -104,7 +104,7 @@ namespace WebUI { static uint64_t fsAvail(const char* fs); }; - extern Web_Server web_server; + extern Web_Server webServer; } #endif diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 44bd1b1eb..d2223593b 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -155,22 +155,19 @@ namespace WebUI { } #endif - static Error setSystemMode(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP444 - parameter = trim(parameter); - if (strcasecmp(parameter, "RESTART") != 0) { - out << "Parameter must be RESTART" << '\n'; - return Error::InvalidValue; - } + static Error restart(char* parameter, AuthenticationLevel auth_level, Channel& out) { log_info("Restarting"); COMMANDS::restart_MCU(); return Error::Ok; } - static Error restart(char* parameter, AuthenticationLevel auth_level, Channel& out) { + static Error setSystemMode(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP444 parameter = trim(parameter); - log_info("Restarting"); - COMMANDS::restart_MCU(); - return Error::Ok; + if (strcasecmp(parameter, "RESTART") != 0) { + out << "Parameter must be RESTART" << '\n'; + return Error::InvalidValue; + } + return restart(parameter, auth_level, out); } static Error showSysStats(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP420 diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index 721c1abca..2610b5550 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -14,8 +14,8 @@ WebUI::WiFiConfig wifi_config; # include "WifiServices.h" // wifi_services.start() etc. # include "WebSettings.h" // split_params(), get_params() -# include "WebServer.h" // web_server.port() -# include "TelnetServer.h" // telnet_server +# include "WebServer.h" // webServer.port() +# include "TelnetServer.h" // telnetServer # include "NotificationsService.h" // notificationsservice # include @@ -109,8 +109,8 @@ namespace WebUI { out << "Available Size for update: " << formatBytes(flashsize) << '\n'; out << "Available Size for LocalFS: " << formatBytes(LocalFS.totalBytes()) << '\n'; - out << "Web port: " << String(web_server.port()) << '\n'; - out << "Data port: " << String(telnet_server.port()) << '\n'; + out << "Web port: " << String(webServer.port()) << '\n'; + out << "Data port: " << String(telnetServer.port()) << '\n'; out << "Hostname: " << wifi_config.Hostname() << '\n'; } @@ -220,9 +220,9 @@ namespace WebUI { break; } - out << "Notifications: " << (notificationsservice.started() ? "Enabled" : "Disabled"); - if (notificationsservice.started()) { - out << "(" << notificationsservice.getTypeString() << ")"; + out << "Notifications: " << (notificationsService.started() ? "Enabled" : "Disabled"); + if (notificationsService.started()) { + out << "(" << notificationsService.getTypeString() << ")"; } out << '\n'; } @@ -297,7 +297,7 @@ namespace WebUI { String WiFiConfig::webInfo() { String s = " # webcommunication: Sync: "; - s += String(web_server.port() + 1); + s += String(webServer.port() + 1); s += ":"; switch (WiFi.getMode()) { case WIFI_MODE_AP: @@ -342,7 +342,7 @@ namespace WebUI { if (WiFi.getMode() == WIFI_MODE_APSTA) { result += "]\n[MSG:"; } - result += "Mode=AP:SSDI="; + result += "Mode=AP:SSID="; wifi_config_t conf; esp_wifi_get_config(WIFI_IF_AP, &conf); result += (const char*)conf.ap.ssid; @@ -535,7 +535,7 @@ namespace WebUI { break; } log_info(msg); - COMMANDS::wait(2000); + delay_ms(2000); // Give it some time to connect } return false; } @@ -748,11 +748,7 @@ namespace WebUI { /** * Handle not critical actions that must be done in sync environment */ - void WiFiConfig::handle() { - //Services - COMMANDS::wait(0); - wifi_services.handle(); - } + void WiFiConfig::handle() { wifi_services.handle(); } Error WiFiConfig::listAPs(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP410 JSONencoder j(false, out); diff --git a/FluidNC/src/WebUI/WifiServices.cpp b/FluidNC/src/WebUI/WifiServices.cpp index 2c470734f..a54d06e59 100644 --- a/FluidNC/src/WebUI/WifiServices.cpp +++ b/FluidNC/src/WebUI/WifiServices.cpp @@ -94,18 +94,18 @@ namespace WebUI { log_info("Start mDNS with hostname:http://" << h << ".local/"); } } - web_server.begin(); - telnet_server.begin(); - notificationsservice.begin(); + webServer.begin(); + telnetServer.begin(); + notificationsService.begin(); //be sure we are not is mixed mode in setup WiFi.scanNetworks(true); return no_error; } void WiFiServices::end() { - notificationsservice.end(); - telnet_server.end(); - web_server.end(); + notificationsService.end(); + telnetServer.end(); + webServer.end(); //stop OTA ArduinoOTA.end(); @@ -115,7 +115,6 @@ namespace WebUI { } void WiFiServices::handle() { - COMMANDS::wait(0); //to avoid mixed mode due to scan network if (WiFi.getMode() == WIFI_AP_STA) { // In principle it should be sufficient to check for != WIFI_SCAN_RUNNING, @@ -126,7 +125,8 @@ namespace WebUI { } } ArduinoOTA.handle(); - web_server.handle(); + webServer.handle(); + telnetServer.handle(); } } #endif diff --git a/FluidNC/src/lineedit.cpp b/FluidNC/src/lineedit.cpp index bc1f8b651..544db9bb7 100644 --- a/FluidNC/src/lineedit.cpp +++ b/FluidNC/src/lineedit.cpp @@ -458,6 +458,12 @@ bool Lineedit::realtime(int c) { // Returns true when the line is complete bool Lineedit::step(int c) { + // Regardless of editing mode, ^L turns off editing/echoing + if (c == CTRL('l')) { + editing = false; + return false; + } + if (!editing) { if (c < ' ') { if (c == '\r' || c == '\n') { diff --git a/FluidNC/src/xmodem.cpp b/FluidNC/src/xmodem.cpp index 448aa4ccf..247569e8b 100644 --- a/FluidNC/src/xmodem.cpp +++ b/FluidNC/src/xmodem.cpp @@ -33,19 +33,22 @@ */ #include "xmodem.h" -#include +// #include -static Uart* serialPort; -static Print* file; +static Channel* serialPort; +static Print* file; static int _inbyte(uint16_t timeout) { uint8_t data; - auto res = serialPort->readBytes(&data, 1, timeout); + auto res = serialPort->timedReadBytes(&data, 1, timeout); return res != 1 ? -1 : data; } static void _outbyte(int c) { serialPort->write((uint8_t)c); } +static void _outbytes(uint8_t* buf, size_t len) { + serialPort->write(buf, len); +} /* CRC16 implementation acording to CCITT standards */ @@ -148,9 +151,7 @@ static void write_packet(uint8_t* buf, size_t packet_len, size_t& total_len) { memcpy(held_packet, buf, packet_len); held = true; } -int xmodemReceive(Uart* serial, Channel* out) { - bool oldCr = serial->setCr(false); - vTaskDelay(1000); +int xmodemReceive(Channel* serial, FileStream* out) { serialPort = serial; file = out; @@ -182,13 +183,11 @@ int xmodemReceive(Uart* serial, Channel* out) { flush_packet(bufsz, len); _outbyte(ACK); flushinput(); - serial->setCr(oldCr); return len; /* normal end */ case CAN: if ((c = _inbyte(DLY_1S)) == CAN) { flushinput(); _outbyte(ACK); - serial->setCr(oldCr); return -1; /* canceled by remote */ } break; @@ -205,7 +204,6 @@ int xmodemReceive(Uart* serial, Channel* out) { _outbyte(CAN); _outbyte(CAN); _outbyte(CAN); - serial->setCr(oldCr); return -2; /* sync error */ start_recv: @@ -231,7 +229,6 @@ int xmodemReceive(Uart* serial, Channel* out) { _outbyte(CAN); _outbyte(CAN); _outbyte(CAN); - serial->setCr(oldCr); return -3; /* too many retry error */ } _outbyte(ACK); @@ -241,10 +238,9 @@ int xmodemReceive(Uart* serial, Channel* out) { flushinput(); _outbyte(NAK); } - serial->setCr(oldCr); } -int xmodemTransmit(Uart* serial, Channel* in) { +int xmodemTransmit(Channel* serial, FileStream* infile) { serialPort = serial; uint8_t xbuff[1030]; /* 1024 for XModem 1k + 3 head chars + 2 crc + nul */ @@ -294,7 +290,7 @@ int xmodemTransmit(Uart* serial, Channel* in) { xbuff[1] = packetno; xbuff[2] = ~packetno; - auto nbytes = in->readBytes(&xbuff[3], bufsz); + auto nbytes = infile->read(&xbuff[3], bufsz); if (nbytes > 0) { while (nbytes < bufsz) { xbuff[3 + nbytes] = CTRLZ; @@ -312,9 +308,7 @@ int xmodemTransmit(Uart* serial, Channel* in) { xbuff[bufsz + 3] = ccks; } for (retry = 0; retry < MAXRETRANS; ++retry) { - for (i = 0; i < bufsz + 4 + (crc ? 1 : 0); ++i) { - _outbyte(xbuff[i]); - } + _outbytes(xbuff, bufsz + 4 + (crc ? 1 : 0)); if ((c = _inbyte(DLY_1S)) >= 0) { switch (c) { case ACK: diff --git a/FluidNC/src/xmodem.h b/FluidNC/src/xmodem.h index d158fd76a..d3cb010fd 100644 --- a/FluidNC/src/xmodem.h +++ b/FluidNC/src/xmodem.h @@ -1,6 +1,7 @@ #pragma once -#include "Uart.h" +#include "Channel.h" +#include "FileStream.h" -int xmodemReceive(Uart* serial, Channel* out); -int xmodemTransmit(Uart* serial, Channel* out); +int xmodemReceive(Channel* serial, FileStream* outfile); +int xmodemTransmit(Channel* serial, FileStream* infile); diff --git a/example_configs/WallPlotter.yaml b/example_configs/WallPlotter.yaml new file mode 100644 index 000000000..777c2f456 --- /dev/null +++ b/example_configs/WallPlotter.yaml @@ -0,0 +1,110 @@ +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: 600 + max_pulse_us: 2300 + + diff --git a/fluidterm/fluidterm.exe b/fluidterm/fluidterm.exe index e8f945a48..62143e9c7 100644 Binary files a/fluidterm/fluidterm.exe and b/fluidterm/fluidterm.exe differ diff --git a/fluidterm/fluidterm.py b/fluidterm/fluidterm.py index 895a63a5e..f03a08665 100644 --- a/fluidterm/fluidterm.py +++ b/fluidterm/fluidterm.py @@ -722,6 +722,7 @@ def writer(self): except: self.alive = False raise + self.disable_fluid_echo(); def handle_menu_key(self, c): """Implement a simple menu / settings""" @@ -906,6 +907,10 @@ def enable_fluid_echo(self): right_arrow = '\x1b[C' self.serial.write(self.tx_encoder.encode(right_arrow)) + def disable_fluid_echo(self): + ctrl_l = '\x0c' + self.serial.write(self.tx_encoder.encode(ctrl_l)) + def reset_fluidnc(self): """Pulse the reset line for FluidNC""" self.console.write("Resetting MCU\n") diff --git a/platformio.ini b/platformio.ini index 5b3cebe78..55c022c2f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -62,7 +62,6 @@ board_build.partitions = min_spiffs.csv ; For 4M ESP32 monitor_speed = 115200 monitor_flags = --eol=LF - --filter=esp32_exception_decoder monitor_filters=esp32_exception_decoder board_build.f_flash = 80000000L build_flags = ${common.build_flags}