From 3ebb3642aab0ec2a66cb4ac6dd50ced5598909da Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Tue, 24 Feb 2026 15:45:05 +0000 Subject: [PATCH 1/5] Initial plan From 42ffd7f18e12811347a0c6d57f8bbedf4e5e5906 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Tue, 24 Feb 2026 15:52:33 +0000 Subject: [PATCH 2/5] Fix ESP32 Arduino 3.x compilation errors: vPort*, ledcAttach*, TIMERG0 Co-authored-by: nsiatras <6023918+nsiatras@users.noreply.github.com> --- RabbitGRBL/src/Serial.cpp | 8 ++++---- RabbitGRBL/src/Spindles/Spindle_PWM.cpp | 6 ++---- RabbitGRBL/src/Stepper.cpp | 7 +++++++ RabbitGRBL/src/UserOutputs/AnalogOutput.cpp | 7 +++---- 4 files changed, 16 insertions(+), 12 deletions(-) diff --git a/RabbitGRBL/src/Serial.cpp b/RabbitGRBL/src/Serial.cpp index ad972e7..5efe271 100644 --- a/RabbitGRBL/src/Serial.cpp +++ b/RabbitGRBL/src/Serial.cpp @@ -95,9 +95,9 @@ void clientCheckTask(void *pvParameters) } else { - vTaskEnterCritical(&myMutex); + vPortEnterCritical(&myMutex); client_buffer.write(data); - vTaskExitCritical(&myMutex); + vPortExitCritical(&myMutex); } } // while something available @@ -109,9 +109,9 @@ void clientCheckTask(void *pvParameters) int client_read() { // vPortEnterCritical(&myMutex); - vTaskEnterCritical(&myMutex); + vPortEnterCritical(&myMutex); int data = client_buffer.read(); - vTaskExitCritical(&myMutex); + vPortExitCritical(&myMutex); // vPortExitCritical(&myMutex); return data; } diff --git a/RabbitGRBL/src/Spindles/Spindle_PWM.cpp b/RabbitGRBL/src/Spindles/Spindle_PWM.cpp index b204cec..41975ac 100644 --- a/RabbitGRBL/src/Spindles/Spindle_PWM.cpp +++ b/RabbitGRBL/src/Spindles/Spindle_PWM.cpp @@ -101,12 +101,10 @@ namespace Spindles fInvertPWM = invert; - // Setup the PWM channel - ledcSetup(fPWMChannelNumber, (double)fPWMFrequency, fPWMPrecision); + // Setup the PWM channel and attach it to the output pin + ledcAttachChannel(fOutputPin, (double)fPWMFrequency, fPWMPrecision, fPWMChannelNumber); - // Attach the PWM to the output pin pinMode(fOutputPin, OUTPUT); - ledcAttachPin(fOutputPin, fPWMChannelNumber); } void PWM::Stop() diff --git a/RabbitGRBL/src/Stepper.cpp b/RabbitGRBL/src/Stepper.cpp index e106a7e..9363dbb 100644 --- a/RabbitGRBL/src/Stepper.cpp +++ b/RabbitGRBL/src/Stepper.cpp @@ -26,6 +26,8 @@ #include "Grbl.h" #include +#include "soc/timer_group_struct.h" +#include "esp_idf_version.h" // Stores the planner block Bresenham algorithm execution data for the segments in the segment // buffer. Normally, this buffer is partially in-use, but, for the worst case scenario, it will @@ -200,7 +202,12 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // // When handling an interrupt within an interrupt serivce routine (ISR), the interrupt status bit // needs to be explicitly cleared. + // Clear the interrupt status bit (register name changed in ESP-IDF 5.x). +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 0, 0) + TIMERG0.int_clr.t0 = 1; +#else TIMERG0.int_clr_timers.t0 = 1; +#endif bool expected = false; if (busy.compare_exchange_strong(expected, true)) diff --git a/RabbitGRBL/src/UserOutputs/AnalogOutput.cpp b/RabbitGRBL/src/UserOutputs/AnalogOutput.cpp index 609b9b8..953b062 100644 --- a/RabbitGRBL/src/UserOutputs/AnalogOutput.cpp +++ b/RabbitGRBL/src/UserOutputs/AnalogOutput.cpp @@ -49,9 +49,8 @@ namespace UserOutput return; } - ledcSetup(_pwm_channel, _pwm_frequency, _resolution_bits); - ledcAttachPin(this->getPinNumber(), _pwm_channel); - ledcWrite(_pwm_channel, 0); + ledcAttach(this->getPinNumber(), _pwm_frequency, _resolution_bits); + ledcWrite(this->getPinNumber(), 0); MessageSender::SendMessage(EMessageLevel::Info, "User Analog Output:%d on Pin:%s Freq:%0.0fHz", this->getNumber(), pinName(this->getPinNumber()).c_str(), _pwm_frequency); } @@ -76,7 +75,7 @@ namespace UserOutput } _current_value = numerator; - ledcWrite(_pwm_channel, numerator); + ledcWrite(this->getPinNumber(), numerator); return true; } From 0ba127adfc651d9dbbcfef04849875d6c33ddd77 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Tue, 24 Feb 2026 15:56:40 +0000 Subject: [PATCH 3/5] Fix Stepper.cpp: replace TIMERG0 register access with portable driver API Co-authored-by: nsiatras <6023918+nsiatras@users.noreply.github.com> --- RabbitGRBL/src/Stepper.cpp | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/RabbitGRBL/src/Stepper.cpp b/RabbitGRBL/src/Stepper.cpp index 9363dbb..89d08a1 100644 --- a/RabbitGRBL/src/Stepper.cpp +++ b/RabbitGRBL/src/Stepper.cpp @@ -26,8 +26,6 @@ #include "Grbl.h" #include -#include "soc/timer_group_struct.h" -#include "esp_idf_version.h" // Stores the planner block Bresenham algorithm execution data for the segments in the segment // buffer. Normally, this buffer is partially in-use, but, for the worst case scenario, it will @@ -200,21 +198,17 @@ void IRAM_ATTR onStepperDriverTimer(void *para) { // Timer ISR, normally takes a step. // - // When handling an interrupt within an interrupt serivce routine (ISR), the interrupt status bit + // When handling an interrupt within an interrupt service routine (ISR), the interrupt status bit // needs to be explicitly cleared. - // Clear the interrupt status bit (register name changed in ESP-IDF 5.x). -#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(5, 0, 0) - TIMERG0.int_clr.t0 = 1; -#else - TIMERG0.int_clr_timers.t0 = 1; -#endif + // Clear the interrupt status bit using the ISR-safe driver API. + timer_group_clr_intr_status_in_isr(STEP_TIMER_GROUP, STEP_TIMER_INDEX); bool expected = false; if (busy.compare_exchange_strong(expected, true)) { stepper_pulse_func(); - TIMERG0.hw_timer[STEP_TIMER_INDEX].config.alarm_en = TIMER_ALARM_EN; + timer_group_enable_alarm_in_isr(STEP_TIMER_GROUP, STEP_TIMER_INDEX); busy.store(false); } @@ -1086,7 +1080,7 @@ void IRAM_ATTR Stepper_Timer_Start() timer_set_counter_value(STEP_TIMER_GROUP, STEP_TIMER_INDEX, 0x00000000ULL); timer_start(STEP_TIMER_GROUP, STEP_TIMER_INDEX); - TIMERG0.hw_timer[STEP_TIMER_INDEX].config.alarm_en = TIMER_ALARM_EN; + timer_set_alarm(STEP_TIMER_GROUP, STEP_TIMER_INDEX, TIMER_ALARM_EN); } void IRAM_ATTR Stepper_Timer_Stop() From 22a6642af5220c5c43e84286dbe6d06421bead54 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Tue, 24 Feb 2026 16:04:26 +0000 Subject: [PATCH 4/5] Fix Limits.cpp: guard detachInterrupt calls with limits_isr_attached flag Co-authored-by: nsiatras <6023918+nsiatras@users.noreply.github.com> --- RabbitGRBL/src/Limits.cpp | 24 ++++++++++++++++++------ 1 file changed, 18 insertions(+), 6 deletions(-) diff --git a/RabbitGRBL/src/Limits.cpp b/RabbitGRBL/src/Limits.cpp index c2279bd..46d92f3 100644 --- a/RabbitGRBL/src/Limits.cpp +++ b/RabbitGRBL/src/Limits.cpp @@ -32,6 +32,12 @@ uint8_t n_homing_locate_cycle = NHomingLocateCycle; xQueueHandle limit_sw_queue; // used by limit switch debouncing +// Tracks whether limit switch ISRs are currently attached. +// Guards detachInterrupt() calls so they are never issued before +// attachInterrupt() has been called (ESP32 Arduino 3.x requires the GPIO ISR +// service to be installed before gpio_isr_handler_remove() can be called). +static bool limits_isr_attached = false; + // Homing axis search distance multiplier. Computed by this value times the cycle travel. #ifndef HOMING_AXIS_SEARCH_SCALAR #define HOMING_AXIS_SEARCH_SCALAR 1.1 // Must be > 1 to ensure limit switch will be engaged. @@ -329,20 +335,21 @@ void limits_init() if (hard_limits->get()) { attachInterrupt(pin, isr_limit_switches, CHANGE); + limits_isr_attached = true; } - else + else if (limits_isr_attached) { detachInterrupt(pin); } - - /*if (limit_sw_queue == NULL) - { - MessageSender::SendMessage(EMessageLevel::Info, "%s limit switch on pin %s", reportAxisNameMsg(axis, gang_index), pinName(pin).c_str()); - }*/ } } } + if (!hard_limits->get()) + { + limits_isr_attached = false; + } + // setup task used for debouncing if (limit_sw_queue == NULL) { @@ -359,6 +366,10 @@ void limits_init() // Disables hard limits. void limits_disable() { + if (!limits_isr_attached) + { + return; + } auto n_axis = number_axis->get(); for (int axis = 0; axis < n_axis; axis++) { @@ -371,6 +382,7 @@ void limits_disable() } } } + limits_isr_attached = false; } // Returns limit state as a bit-wise uint8 variable. Each bit indicates an axis limit, where From 69465dda244aceb3b9a4b819adf920938e338146 Mon Sep 17 00:00:00 2001 From: "copilot-swe-agent[bot]" <198982749+Copilot@users.noreply.github.com> Date: Tue, 24 Feb 2026 16:35:31 +0000 Subject: [PATCH 5/5] Fix Stepper_RMT: replace rmt_tx_start() with ISR-safe direct register writes Co-authored-by: nsiatras <6023918+nsiatras@users.noreply.github.com> --- .../src/Motors/MotorsByType/Stepper_RMT.cpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/RabbitGRBL/src/Motors/MotorsByType/Stepper_RMT.cpp b/RabbitGRBL/src/Motors/MotorsByType/Stepper_RMT.cpp index 4700f94..7ee0670 100644 --- a/RabbitGRBL/src/Motors/MotorsByType/Stepper_RMT.cpp +++ b/RabbitGRBL/src/Motors/MotorsByType/Stepper_RMT.cpp @@ -21,6 +21,7 @@ */ #include "Stepper_RMT.h" +#include "soc/rmt_struct.h" Stepper_RMT::Stepper_RMT(uint8_t axis_index, uint8_t step_pin, uint8_t dir_pin, uint8_t disable_pin) : Motor(axis_index), _step_pin(step_pin), _dir_pin(dir_pin), _disable_pin(disable_pin) @@ -114,13 +115,14 @@ rmt_channel_t Stepper_RMT::get_next_RMT_chan_num() void Stepper_RMT::Step() { - // Use official ESP-IDF API instead of direct register access. - // rmt_tx_start(channel, true) resets the memory read pointer (mem_rd_rst) - // and starts transmission — equivalent to the previous low-level register writes: - // RMT.conf_ch[_rmt_chan_num].conf1.mem_rd_rst = 1; - // RMT.conf_ch[_rmt_chan_num].conf1.tx_start = 1; - // but safe, portable, and compatible across ESP-IDF versions. - rmt_tx_start(_rmt_chan_num, true); + // Direct ISR-safe register writes: reset the memory read pointer, then start TX. + // rmt_tx_start() is not reliably ISR-safe in ESP32 Arduino 3.x (ESP-IDF 5.x) because + // it acquires internal driver state and can silently fail, causing missed step pulses. + // These three writes are exactly what rmt_ll_tx_reset_pointer() + rmt_ll_tx_enable() + // (the internals of rmt_tx_start) do, and are always safe to call from an ISR. + RMT.conf_ch[_rmt_chan_num].conf1.mem_rd_rst = 1; // reset memory read pointer + RMT.conf_ch[_rmt_chan_num].conf1.mem_rd_rst = 0; // clear reset before starting + RMT.conf_ch[_rmt_chan_num].conf1.tx_start = 1; // start transmission } void Stepper_RMT::Unstep()