Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 18 additions & 6 deletions RabbitGRBL/src/Limits.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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)
{
Expand All @@ -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++)
{
Expand All @@ -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
Expand Down
16 changes: 9 additions & 7 deletions RabbitGRBL/src/Motors/MotorsByType/Stepper_RMT.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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()
Expand Down
8 changes: 4 additions & 4 deletions RabbitGRBL/src/Serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,9 @@ void clientCheckTask(void *pvParameters)
}
else
{
vTaskEnterCritical(&myMutex);
vPortEnterCritical(&myMutex);
client_buffer.write(data);
vTaskExitCritical(&myMutex);
vPortExitCritical(&myMutex);
}
} // while something available

Expand All @@ -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;
}
Expand Down
6 changes: 2 additions & 4 deletions RabbitGRBL/src/Spindles/Spindle_PWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
9 changes: 5 additions & 4 deletions RabbitGRBL/src/Stepper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,16 +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.
TIMERG0.int_clr_timers.t0 = 1;
// 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);
}
Expand Down Expand Up @@ -1079,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()
Expand Down
7 changes: 3 additions & 4 deletions RabbitGRBL/src/UserOutputs/AnalogOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand All @@ -76,7 +75,7 @@ namespace UserOutput
}

_current_value = numerator;
ledcWrite(_pwm_channel, numerator);
ledcWrite(this->getPinNumber(), numerator);

return true;
}
Expand Down
Loading