1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-31 10:01:48 +02:00

st_ naming convention -> Stepper:: namespace

Also fixed a potential number wraparound bug with
idle timer comparision.
This commit is contained in:
Mitch Bradley
2021-07-05 11:22:35 -10:00
parent 7e153cdb26
commit 31bc285bf9
13 changed files with 121 additions and 122 deletions

View File

@@ -89,7 +89,7 @@ void grbl_init() {
}
}
stepper_init(); // Configure stepper pins and interrupt timers
Stepper::init(); // Configure stepper pins and interrupt timers
config->_axes->read_settings();
config->_axes->init();
@@ -160,7 +160,7 @@ static void reset_variables() {
if (spindle) {
spindle->stop();
}
st_reset(); // Clear stepper subsystem variables
Stepper::reset(); // Clear stepper subsystem variables
}
// Sync cleared gcode and planner positions to current system position.

View File

@@ -614,7 +614,7 @@ int IRAM_ATTR i2s_out_set_passthrough() {
i2s_out_pulser_status = WAITING; // Start stopping the pulser (trigger)
}
// It is a function that may be called via i2sOutTask().
// (i2sOutTask() -> stepper_pulse_func() -> st_go_idle() -> Stepper_Timer_Stop() -> this function)
// (i2sOutTask() -> Stepper::pulse_func() -> Stepper::go_idle() -> Stepper_Timer_Stop() -> this function)
// And only i2sOutTask() can change the state to PASSTHROUGH.
// So, to change the state, you need to return to i2sOutTask() as soon as possible.
#else

View File

@@ -51,8 +51,8 @@ Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* can
if (sys.state == State::Idle) {
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
sys.state = State::Jog;
st_prep_buffer();
st_wake_up(); // NOTE: Manual start. No state machine required.
Stepper::prep_buffer();
Stepper::wake_up(); // NOTE: Manual start. No state machine required.
}
}
return Error::Ok;

View File

@@ -230,15 +230,15 @@ static void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) {
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
sys.step_control = {};
sys.step_control.executeSysMotion = true; // Set to execute homing motion and clear existing flags.
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
st_wake_up(); // Initiate motion
Stepper::prep_buffer(); // Prep and fill segment buffer from newly planned block.
Stepper::wake_up(); // Initiate motion
do {
if (approach) {
// Check limit state. Lock out cycle axes when they change.
bit_false(axislock, limits_check(axislock));
sys.homing_axis_lock = axislock;
}
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
Stepper::prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
ExecAlarm alarm = limits_handle_errors(approach, cycle_mask);
if (alarm != ExecAlarm::None) {
@@ -266,7 +266,7 @@ static void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) {
}
}
st_reset(); // Immediately force kill steppers and reset step segment buffer.
Stepper::reset(); // Immediately force kill steppers and reset step segment buffer.
delay_ms(debounce); // Delay to allow transient dynamics to dissipate.
// After the initial approach, we switch to the slow rate for subsequent steps

View File

@@ -276,7 +276,7 @@ bool mc_dwell(int32_t milliseconds) {
inline void RESTORE_STEPPER(int save_stepper) {
if (save_stepper == ST_I2S_STREAM && config->_stepType != ST_I2S_STREAM) {
stepper_switch(ST_I2S_STREAM); /* Put the stepper back on. */
Stepper::switch_mode(ST_I2S_STREAM); /* Put the stepper back on. */
}
}
@@ -339,7 +339,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
// Switch stepper mode to the I2S static (realtime mode)
if (save_stepper == ST_I2S_STREAM) {
stepper_switch(ST_I2S_STATIC); /* Change the stepper to reduce the delay for accurate probing. */
Stepper::switch_mode(ST_I2S_STATIC); /* Change the stepper to reduce the delay for accurate probing. */
}
// Initialize probing control variables
@@ -387,7 +387,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
sys_probe_state = ProbeState::Off; // Ensure probe state monitor is disabled.
protocol_execute_realtime(); // Check and execute run-time commands
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
st_reset(); // Reset step segment buffer.
Stepper::reset(); // Reset step segment buffer.
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
plan_sync_position(); // Sync planner position to current machine position.
if (MESSAGE_PROBE_COORDINATES) {
@@ -410,16 +410,16 @@ void mc_parking_motion(float* parking_target, plan_line_data_t* pl_data) {
if (plan_buffer_line(parking_target, pl_data)) {
sys.step_control.executeSysMotion = true;
sys.step_control.endMotion = false; // Allow parking motion to execute, if feed hold is active.
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
st_prep_buffer();
st_wake_up();
Stepper::parking_setup_buffer(); // Setup step segment buffer for special parking motion case
Stepper::prep_buffer();
Stepper::wake_up();
do {
protocol_exec_rt_system();
if (sys.abort) {
return;
}
} while (sys.step_control.executeSysMotion);
st_parking_restore_buffer(); // Restore step segment buffer to normal run state.
Stepper::parking_restore_buffer(); // Restore step segment buffer to normal run state.
} else {
sys.step_control.executeSysMotion = false;
protocol_exec_rt_system();
@@ -473,7 +473,7 @@ void mc_reset() {
} else {
sys_rt_exec_alarm = ExecAlarm::AbortCycle;
}
st_go_idle(); // Force kill steppers. Position has likely been lost.
Stepper::go_idle(); // Force kill steppers. Position has likely been lost.
}
ganged_mode = gangDual; // in case an error occurred during squaring

View File

@@ -257,7 +257,7 @@ namespace Motors {
if (tstep == 0xFFFFF || tstep < 1) { // if axis is not moving return
return;
}
float feedrate = st_get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
float feedrate = Stepper::get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
info_serial("%s Stallguard %d SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d",
reportAxisNameMsg(axis_index(), dual_axis_index()),

View File

@@ -245,7 +245,7 @@ namespace Motors {
if (tstep == 0xFFFFF || tstep < 1) { // if axis is not moving return
return;
}
float feedrate = st_get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
float feedrate = Stepper::get_realtime_rate(); //* settings.microsteps[axis_index] / 60.0 ; // convert mm/min to Hz
info_serial("%s SG_Val: %04d Rate: %05.0f mm/min SG_Setting:%d",
reportAxisNameMsg(axis_index(), dual_axis_index()),

View File

@@ -147,7 +147,7 @@ static void planner_recalculate() {
if (block_index == block_buffer_planned) { // Only two plannable blocks in buffer. Reverse pass complete.
// Check if the first block is the tail. If so, notify stepper to update its current parameters.
if (block_index == block_buffer_tail) {
st_update_plan_block_parameters();
Stepper::update_plan_block_parameters();
}
} else { // Three or more plan-able blocks
while (block_index != block_buffer_planned) {
@@ -156,7 +156,7 @@ static void planner_recalculate() {
block_index = plan_prev_block_index(block_index);
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
if (block_index == block_buffer_tail) {
st_update_plan_block_parameters();
Stepper::update_plan_block_parameters();
}
// Compute maximum entry speed decelerating over the current block from its exit speed.
if (current->entry_speed_sqr != current->max_entry_speed_sqr) {
@@ -400,7 +400,7 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) {
} else {
convert_delta_vector_to_unit_vector(junction_unit_vec);
float junction_acceleration = limit_acceleration_by_axis_maximum(junction_unit_vec);
float sin_theta_d2 = float(sqrt(0.5f * (1.0f - junction_cos_theta))); // Trig half angle identity. Always positive.
float sin_theta_d2 = float(sqrt(0.5f * (1.0f - junction_cos_theta))); // Trig half angle identity. Always positive.
block->max_junction_speed_sqr =
MAX(MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED,
(junction_acceleration * config->_junctionDeviation * sin_theta_d2) / (1.0f - sin_theta_d2));
@@ -458,7 +458,7 @@ uint8_t plan_get_block_buffer_count() {
// Called after a steppers have come to a complete stop for a feed hold and the cycle is stopped.
void plan_cycle_reinitialize() {
// Re-plan from a complete stop. Reset planner entry speeds and buffer planned pointer.
st_update_plan_block_parameters();
Stepper::update_plan_block_parameters();
block_buffer_planned = block_buffer_tail;
planner_recalculate();
}

View File

@@ -274,18 +274,18 @@ Error home(int cycle) {
int save_stepper = config->_stepType;
if (save_stepper == ST_I2S_STREAM) {
stepper_switch(ST_I2S_STATIC);
Stepper::switch_mode(ST_I2S_STATIC);
}
mc_homing_cycle(cycle);
if (save_stepper == ST_I2S_STREAM && config->_stepType != ST_I2S_STREAM) {
stepper_switch(ST_I2S_STREAM);
Stepper::switch_mode(ST_I2S_STREAM);
}
if (!sys.abort) { // Execute startup scripts after successful homing.
sys.state = State::Idle; // Set to IDLE when complete.
st_go_idle(); // Set steppers to the settings idle state before returning.
Stepper::go_idle(); // Set steppers to the settings idle state before returning.
if (cycle == HOMING_CYCLE_ALL) {
system_execute_startup();
}

View File

@@ -227,10 +227,8 @@ void protocol_main_loop() {
return; // Bail to main() program loop to reset system.
}
// check to see if we should disable the stepper drivers ... esp32 work around for disable in main loop.
if (stepper_idle && config->_idleTime != 255) {
if (uint64_t(esp_timer_get_time()) > stepper_idle_counter) {
config->_axes->set_disable(true);
}
if (Stepper::shouldDisable()) {
config->_axes->set_disable(true);
}
}
return; /* Never reached */
@@ -312,7 +310,7 @@ static void protocol_do_alarm() {
static void protocol_start_holding() {
if (!(sys.suspend.bit.motionCancel || sys.suspend.bit.jogCancel)) { // Block, if already holding.
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
Stepper::update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
sys.step_control = {};
sys.step_control.executeHold = true; // Initiate suspend state with active flag.
}
@@ -424,7 +422,7 @@ static void protocol_do_safety_door() {
if (!sys.suspend.bit.jogCancel && sys.suspend.bit.initiateRestore) { // Actively restoring
// Set hold and reset appropriate control flags to restart parking sequence.
if (sys.step_control.executeSysMotion) {
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
Stepper::update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
sys.step_control = {};
sys.step_control.executeHold = true;
sys.step_control.executeSysMotion = true;
@@ -493,8 +491,8 @@ static void protocol_do_initiate_cycle() {
if (plan_get_current_block() && !sys.suspend.bit.motionCancel) {
sys.suspend.value = 0; // Break suspend state.
sys.state = State::Cycle;
st_prep_buffer(); // Initialize step segment buffer before beginning cycle.
st_wake_up();
Stepper::prep_buffer(); // Initialize step segment buffer before beginning cycle.
Stepper::wake_up();
} else { // Otherwise, do nothing. Set and resume IDLE state.
sys.suspend.value = 0; // Break suspend state.
sys.state = State::Idle;
@@ -584,7 +582,7 @@ static void protocol_do_cycle_stop() {
if (sys.suspend.bit.jogCancel) { // For jog cancel, flush buffers and sync positions.
sys.step_control = {};
plan_reset();
st_reset();
Stepper::reset();
gc_sync_position();
plan_sync_position();
}
@@ -744,7 +742,7 @@ void protocol_exec_rt_system() {
case State::SafetyDoor:
case State::Homing:
case State::Jog:
st_prep_buffer();
Stepper::prep_buffer();
break;
}
}
@@ -1128,7 +1126,7 @@ static void protocol_exec_rt_suspend() {
// Spindle and coolant should already be stopped, but do it again just to be sure.
spindle->spinDown();
config->_coolant->off();
st_go_idle(); // Disable steppers
Stepper::go_idle(); // Disable steppers
while (!(sys.abort)) {
protocol_exec_rt_system(); // Do nothing until reset.
}

View File

@@ -669,11 +669,11 @@ void report_realtime_status(uint8_t client) {
}
// Report realtime feed speed
float rate = Stepper::get_realtime_rate();
if (config->_reportInches) {
sprintf(temp, "|FS:%.1f,%d", st_get_realtime_rate() / MM_PER_INCH, sys.spindle_speed);
} else {
sprintf(temp, "|FS:%.0f,%d", st_get_realtime_rate(), sys.spindle_speed);
rate /= MM_PER_INCH;
}
sprintf(temp, "|FS:%.0f,%d", rate, sys.spindle_speed);
strcat(status, temp);
AxisMask lim_pin_state = limits_get_state();
bool prb_pin_state = config->_probe->get_state();
@@ -778,7 +778,7 @@ void report_realtime_status(uint8_t client) {
strcat(status, config->_sdCard->filename());
}
#ifdef DEBUG_STEPPER_ISR
sprintf(temp, "|ISRs:%d", step_count);
sprintf(temp, "|ISRs:%d", Stepper::isr_count);
strcat(status, temp);
#endif
#ifdef DEBUG_REPORT_HEAP

View File

@@ -34,6 +34,8 @@
#include <atomic>
#include <Arduino.h> // IRAM_ATTR
using namespace Stepper;
// 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
// never exceed the number of accessible stepper buffer segments (SEGMENT_BUFFER_SIZE-1).
@@ -94,9 +96,20 @@ static std::atomic<bool> busy;
static plan_block_t* pl_block; // Pointer to the planner block being prepped
static st_block_t* st_prep_block; // Pointer to the stepper block data being prepped
// esp32 work around for disable in main loop
uint64_t stepper_idle_counter; // used to count down until time to disable stepper drivers
bool stepper_idle;
// The time, in ticks of esp_timer_get_time(), when the steppers should be disabled
static int64_t idleEndTime;
static bool isIdle;
bool Stepper::shouldDisable() {
// "(timer() - EndTime) > 0" is a twos-complement arithmetic trick
// for avoiding problems when the number space wraps around from
// negative to positive or vice-versa. It always works if EndTime
// is set to "timer() + N" where N is less than half the number
// space. Using "timer() > EndTime" fails across the positive to
// negative transition using signed comparison, and across the
// negative to positive transition using unsigned.
return isIdle && config->_idleTime != 255 && (esp_timer_get_time() - idleEndTime) > 0;
}
// Segment preparation data struct. Contains all the necessary information to compute new segments
// based on the current executing planner block.
@@ -190,10 +203,10 @@ EnumItem stepTypes[] = {
*/
// Forward references to functions that are only used herein
static void Stepper_Timer_WritePeriod(uint16_t timerTicks);
static void Stepper_Timer_Init();
static void Stepper_Timer_Start();
static void Stepper_Timer_Stop();
static void timerWritePeriod(uint16_t timerTicks);
static void timerInit();
static void timerStart();
static void timerStop();
// Stepper timer configuration
const int stepTimerNumber = 0;
@@ -202,12 +215,12 @@ hw_timer_t* stepTimer = nullptr; // Handle
// might cause problems if an interrupt takes too long
const bool autoReload = true;
static void stepper_pulse_func();
static void pulse_func();
// Counts stepper ISR invocations. This variable can be inspected
// from the mainline code to determine if the stepper ISR is running,
// since printing from the ISR is not a good idea.
uint32_t step_count = 0;
uint32_t Stepper::isr_count = 0;
// TODO: Replace direct updating of the int32 position counters in the ISR somehow. Perhaps use smaller
// int8 variables and update position counters only when a segment completes. This can get complicated
@@ -219,7 +232,7 @@ void IRAM_ATTR onStepperDriverTimer() {
bool expected = false;
if (busy.compare_exchange_strong(expected, true)) {
++step_count;
++isr_count;
// Using autoReload results is less timing jitter so it is
// probably best to have it on. We keep the variable for
@@ -228,14 +241,14 @@ void IRAM_ATTR onStepperDriverTimer() {
timerWrite(stepTimer, 0ULL);
}
// It is tempting to defer this until after stepper_pulse_func(),
// but if stepper_pulse_func() determines that no more stepping
// It is tempting to defer this until after pulse_func(),
// but if pulse_func() determines that no more stepping
// is required and disables the timer, then that will be undone
// if the re-enable happens afterwards.
timerAlarmEnable(stepTimer);
stepper_pulse_func();
pulse_func();
busy.store(false);
}
@@ -248,7 +261,7 @@ void IRAM_ATTR onStepperDriverTimer() {
* call to this method that might cause variation in the timing. The aim
* is to keep pulse timing as regular as possible.
*/
static void IRAM_ATTR stepper_pulse_func() {
static void IRAM_ATTR pulse_func() {
auto n_axis = config->_axes->_numberAxis;
// If we are using GPIO stepping as opposed to RMT, record the
@@ -266,7 +279,7 @@ static void IRAM_ATTR stepper_pulse_func() {
// Initialize new step segment and load number of steps to execute
st.exec_segment = &segment_buffer[segment_buffer_tail];
// Initialize step segment timing per step and load number of steps to execute.
Stepper_Timer_WritePeriod(st.exec_segment->isrPeriod);
timerWritePeriod(st.exec_segment->isrPeriod);
st.step_count = st.exec_segment->n_step; // NOTE: Can sometimes be zero when moving slow.
// If the new segment starts a new planner block, initialize stepper variables and counters.
// NOTE: When the segment data index changes, this indicates a new planner block.
@@ -287,7 +300,7 @@ static void IRAM_ATTR stepper_pulse_func() {
spindle->setSpeedfromISR(st.exec_segment->spindle_dev_speed);
} else {
// Segment buffer empty. Shutdown.
st_go_idle();
go_idle();
if (sys.state != State::Jog) { // added to prevent ... jog after probing crash
// Ensure pwm is set properly upon completion of rate-controlled motion.
if (st.exec_block != NULL && st.exec_block->is_pwm_rate_adjusted) {
@@ -355,7 +368,7 @@ static void IRAM_ATTR stepper_pulse_func() {
}
}
void stepper_init() {
void Stepper::init() {
busy.store(false);
info_serial("Axis count %d", config->_axes->_numberAxis);
@@ -366,10 +379,10 @@ void stepper_init() {
config->_directionDelayMicroSeconds);
// Other stepper use timer interrupt
Stepper_Timer_Init();
timerInit();
}
void stepper_switch(stepper_id_t new_stepper) {
void Stepper::switch_mode(stepper_id_t new_stepper) {
debug_serial("Switch stepper: %s -> %s", stepTypes[config->_stepType].name, stepTypes[new_stepper].name);
if (config->_stepType == new_stepper) {
// do not need to change
@@ -389,24 +402,24 @@ void stepper_switch(stepper_id_t new_stepper) {
}
// enabled. Startup init and limits call this function but shouldn't start the cycle.
void st_wake_up() {
void Stepper::wake_up() {
//info_serial("st_wake_up");
// Enable stepper drivers.
config->_axes->set_disable(false);
stepper_idle = false;
isIdle = false;
// Enable Stepper Driver Interrupt
Stepper_Timer_Start();
timerStart();
}
// Reset and clear stepper subsystem variables
void st_reset() {
void Stepper::reset() {
// Initialize stepper driver idle state.
if (config->_stepType == ST_I2S_STREAM) {
i2s_out_reset();
}
st_go_idle();
go_idle();
// Initialize stepper algorithm variables.
memset(&prep, 0, sizeof(st_prep_t));
memset(&st, 0, sizeof(stepper_t));
@@ -421,9 +434,9 @@ void st_reset() {
}
// Stepper shutdown
void IRAM_ATTR st_go_idle() {
void IRAM_ATTR Stepper::go_idle() {
// Disable Stepper Driver Interrupt. Allow Stepper Port Reset Interrupt to finish, if active.
Stepper_Timer_Stop();
timerStop();
// Set stepper driver idle state, disabled or enabled, depending on settings and circumstances.
if (((config->_idleTime != 255) || sys_rt_exec_alarm != ExecAlarm::None || sys.state == State::Sleep) && sys.state != State::Homing) {
@@ -433,9 +446,9 @@ void IRAM_ATTR st_go_idle() {
if (sys.state == State::Sleep || sys_rt_exec_alarm != ExecAlarm::None) {
config->_axes->set_disable(true);
} else {
stepper_idle = true; // esp32 work around for disable in main loop
stepper_idle_counter = esp_timer_get_time() + (config->_idleTime * 1000); // * 1000 because the time is in uSecs
// after idle countdown will be disabled in protocol loop
// Setup for shouldDisable()
isIdle = true;
idleEndTime = esp_timer_get_time() + (config->_idleTime * 1000); // * 1000 because the time is in uSecs
}
} else {
config->_axes->set_disable(false);
@@ -446,16 +459,16 @@ void IRAM_ATTR st_go_idle() {
}
// Called by planner_recalculate() when the executing block is updated by the new plan.
void st_update_plan_block_parameters() {
void Stepper::update_plan_block_parameters() {
if (pl_block != NULL) { // Ignore if at start of a new block.
prep.recalculate_flag.recalculate = 1;
pl_block->entry_speed_sqr = prep.current_speed * prep.current_speed; // Update entry speed.
pl_block = NULL; // Flag st_prep_segment() to load and check active velocity profile.
pl_block = NULL; // Flag prep_segment() to load and check active velocity profile.
}
}
// Changes the run state of the step segment buffer to execute the special parking motion.
void st_parking_setup_buffer() {
void Stepper::parking_setup_buffer() {
// Store step execution data of partially completed block, if necessary.
if (prep.recalculate_flag.holdPartialBlock) {
prep.last_st_block_index = prep.st_block_index;
@@ -470,7 +483,7 @@ void st_parking_setup_buffer() {
}
// Restores the step segment buffer to the normal run state after a parking motion.
void st_parking_restore_buffer() {
void Stepper::parking_restore_buffer() {
// Restore step execution data and flags of partially completed block, if necessary.
if (prep.recalculate_flag.holdPartialBlock) {
st_prep_block = &st_block_buffer[prep.last_st_block_index];
@@ -489,7 +502,7 @@ void st_parking_restore_buffer() {
}
// Increments the step segment buffer block data ring buffer.
static uint8_t st_next_block_index(uint8_t block_index) {
static uint8_t next_block_index(uint8_t block_index) {
block_index++;
return block_index == (SEGMENT_BUFFER_SIZE - 1) ? 0 : block_index;
}
@@ -507,7 +520,7 @@ static uint8_t st_next_block_index(uint8_t block_index) {
Currently, the segment buffer conservatively holds roughly up to 40-50 msec of steps.
NOTE: Computation units are in steps, millimeters, and minutes.
*/
void st_prep_buffer() {
void Stepper::prep_buffer() {
// Block step prep buffer, while in a suspend state and there is no suspend motion to execute.
if (sys.step_control.endMotion) {
return;
@@ -536,7 +549,7 @@ void st_prep_buffer() {
}
} else {
// Load the Bresenham stepping data for the block.
prep.st_block_index = st_next_block_index(prep.st_block_index);
prep.st_block_index = next_block_index(prep.st_block_index);
// Prepare and copy Bresenham algorithm segment data from the new planner block, so that
// when the segment buffer completes the planner block, it may be discarded when the
// segment buffer finishes the prepped block, but the stepper ISR is still executing it.
@@ -801,7 +814,7 @@ void st_prep_buffer() {
}
sys.step_control.updateSpindleSpeed = false;
}
prep_segment->spindle_speed = prep.current_spindle_speed;
prep_segment->spindle_speed = prep.current_spindle_speed;
prep_segment->spindle_dev_speed = spindle->mapSpeed(prep.current_spindle_speed); // Reload segment PWM value
/* -----------------------------------------------------------------------------------
@@ -902,7 +915,7 @@ void st_prep_buffer() {
// however is not exactly the current speed, but the speed computed in the last step segment
// in the segment buffer. It will always be behind by up to the number of segment blocks (-1)
// divided by the ACCELERATION TICKS PER SECOND in seconds.
float st_get_realtime_rate() {
float Stepper::get_realtime_rate() {
switch (sys.state) {
case State::Cycle:
case State::Homing:
@@ -916,7 +929,7 @@ float st_get_realtime_rate() {
}
// The argument is in units of ticks of the timer that generates ISRs
static void IRAM_ATTR Stepper_Timer_WritePeriod(uint16_t timerTicks) {
static void IRAM_ATTR timerWritePeriod(uint16_t timerTicks) {
if (config->_stepType == ST_I2S_STREAM) {
// 1 tick = fTimers / fStepperTimer
// Pulse ISR is called for each tick of alarm_val.
@@ -927,22 +940,22 @@ static void IRAM_ATTR Stepper_Timer_WritePeriod(uint16_t timerTicks) {
}
}
static void IRAM_ATTR Stepper_Timer_Init() {
static void IRAM_ATTR timerInit() {
const bool isEdge = false;
const bool countUp = true;
// Prepare stepping interrupt callbacks. The one that is actually
// used is determined by Stepper_Timer_Start() and _Stop()
// used is determined by timerStart() and timerStop()
// Register stepper_pulse_func with the I2S subsystem
i2s_out_set_pulse_callback(stepper_pulse_func);
// Register pulse_func with the I2S subsystem
i2s_out_set_pulse_callback(pulse_func);
// Setup a timer for direct stepping
stepTimer = timerBegin(stepTimerNumber, fTimers / fStepperTimer, countUp);
timerAttachInterrupt(stepTimer, onStepperDriverTimer, isEdge);
}
static void IRAM_ATTR Stepper_Timer_Start() {
static void IRAM_ATTR timerStart() {
if (config->_stepType == ST_I2S_STREAM) {
i2s_out_set_stepping();
} else {
@@ -951,19 +964,10 @@ static void IRAM_ATTR Stepper_Timer_Start() {
}
}
static void IRAM_ATTR Stepper_Timer_Stop() {
static void IRAM_ATTR timerStop() {
if (config->_stepType == ST_I2S_STREAM) {
i2s_out_set_passthrough();
} else if (stepTimer) {
timerAlarmDisable(stepTimer);
}
}
bool get_stepper_disable() { // returns true if steppers are disabled
auto axesConfig = config->_axes;
if (axesConfig->_sharedStepperDisable.defined()) {
bool disabled = axesConfig->_sharedStepperDisable.read();
return disabled;
}
return false; // they are never disabled if there is no pin defined
}

View File

@@ -35,42 +35,39 @@ enum stepper_id_t {
ST_I2S_STREAM,
};
// esp32 work around for diable in main loop
extern uint64_t stepper_idle_counter;
extern bool stepper_idle;
namespace Stepper {
// Is it time to disable the steppers?
bool shouldDisable();
void stepper_init();
void stepper_switch(stepper_id_t new_stepper);
void init();
void switch_mode(stepper_id_t new_stepper);
// Enable steppers, but cycle does not start unless called by motion control or realtime command.
void st_wake_up();
// Enable steppers, but cycle does not start unless called by motion control or realtime command.
void wake_up();
// Immediately disables steppers
void st_go_idle();
// Immediately disables steppers
void go_idle();
// Reset the stepper subsystem variables
void st_reset();
// Reset the stepper subsystem variables
void reset();
// Changes the run state of the step segment buffer to execute the special parking motion.
void st_parking_setup_buffer();
// Changes the run state of the step segment buffer to execute the special parking motion.
void parking_setup_buffer();
// Restores the step segment buffer to the normal run state after a parking motion.
void st_parking_restore_buffer();
// Restores the step segment buffer to the normal run state after a parking motion.
void parking_restore_buffer();
// Reloads step segment buffer. Called continuously by realtime execution system.
void st_prep_buffer();
// Reloads step segment buffer. Called continuously by realtime execution system.
void prep_buffer();
// Called by planner_recalculate() when the executing block is updated by the new plan.
void st_update_plan_block_parameters();
// Called by planner_recalculate() when the executing block is updated by the new plan.
void update_plan_block_parameters();
// Called by realtime status reporting if realtime rate reporting is enabled in config.h.
float st_get_realtime_rate();
// Called by realtime status reporting if realtime rate reporting is enabled in config.h.
float get_realtime_rate();
// disable (or enable) steppers via STEPPERS_DISABLE_PIN
bool get_stepper_disable(); // returns the state of the pin
void set_stepper_pins_on(uint8_t onMask);
void set_direction_pins_on(uint8_t onMask);
extern uint32_t isr_count; // for debugging only
}
// private
extern EnumItem stepTypes[];
extern uint32_t step_count;