mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 10:53:01 +02:00
Fixed typo
This commit is contained in:
@@ -134,7 +134,7 @@ bool user_defined_homing(uint8_t cycle_mask) {
|
||||
// convert back to motor steps
|
||||
inverse_kinematics(target);
|
||||
|
||||
pl_data->feed_rate = homing_rate; // feed or seek rates
|
||||
pl_data->feed_rate = homing_rate; // Set current homing rate.
|
||||
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.
|
||||
@@ -148,23 +148,18 @@ bool user_defined_homing(uint8_t cycle_mask) {
|
||||
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
|
||||
// Exit routines: No time to run protocol_execute_realtime() in this loop.
|
||||
if (sys_safetyDoor || sys_reset || sys_cycleStop) {
|
||||
ExecState rt_exec_state;
|
||||
rt_exec_state.value = sys_get_rt_exec_state().value;
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
if (rt_exec_state.bit.reset) {
|
||||
if (sys_reset) {
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailReset;
|
||||
}
|
||||
// Homing failure condition: Safety door was opened.
|
||||
if (rt_exec_state.bit.safetyDoor) {
|
||||
} else if (sys_safetyDoor) {
|
||||
// Homing failure condition: Safety door was opened.
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailDoor;
|
||||
}
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
if (!approach && (limits_get_state() & cycle_mask)) {
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailPulloff;
|
||||
}
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
if (approach && rt_exec_state.bit.cycleStop) {
|
||||
} else if (approach) { // sys_cycleStop must be true if we get this far
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailApproach;
|
||||
} else if (limits_get_state() & cycle_mask) {
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailPulloff;
|
||||
}
|
||||
|
||||
if (sys_rt_exec_alarm != ExecAlarm::None) {
|
||||
@@ -172,11 +167,11 @@ bool user_defined_homing(uint8_t cycle_mask) {
|
||||
mc_reset(); // Stop motors, if they are running.
|
||||
protocol_execute_realtime();
|
||||
return true;
|
||||
} else {
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
sys_cycleStop = false;
|
||||
break;
|
||||
}
|
||||
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
sys_cycleStop = false;
|
||||
break;
|
||||
}
|
||||
} while (!switch_touched);
|
||||
|
||||
|
@@ -174,23 +174,18 @@ void limits_go_home(uint8_t cycle_mask) {
|
||||
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
|
||||
// Exit routines: No time to run protocol_execute_realtime() in this loop.
|
||||
if (sys_safetyDoor || sys_reset || sys_cycleStop) {
|
||||
ExecState rt_exec_state;
|
||||
rt_exec_state.value = sys_get_rt_exec_state().value;
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
if (rt_exec_state.bit.reset) {
|
||||
if (sys_reset) {
|
||||
// Homing failure condition: Reset issued during cycle.
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailReset;
|
||||
}
|
||||
// Homing failure condition: Safety door was opened.
|
||||
if (rt_exec_state.bit.safetyDoor) {
|
||||
} else if (sys_safetyDoor) {
|
||||
// Homing failure condition: Safety door was opened.
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailDoor;
|
||||
}
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
if (!approach && (limits_get_state() & cycle_mask)) {
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailPulloff;
|
||||
}
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
if (approach && rt_exec_state.bit.cycleStop) {
|
||||
} else if (approach) { // sys_cycleStop must be true if we get this far
|
||||
// Homing failure condition: Limit switch not found during approach.
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailApproach;
|
||||
} else if (limits_get_state() & cycle_mask) {
|
||||
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||
sys_rt_exec_alarm = ExecAlarm::HomingFailPulloff;
|
||||
}
|
||||
|
||||
if (sys_rt_exec_alarm != ExecAlarm::None) {
|
||||
@@ -198,11 +193,11 @@ void limits_go_home(uint8_t cycle_mask) {
|
||||
mc_reset(); // Stop motors, if they are running.
|
||||
protocol_execute_realtime();
|
||||
return;
|
||||
} else {
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
sys_cycleStop = false;
|
||||
break;
|
||||
}
|
||||
|
||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||
sys_cycleStop = false;
|
||||
break;
|
||||
}
|
||||
} while (STEP_MASK & axislock);
|
||||
#ifdef USE_I2S_STEPS
|
||||
|
@@ -222,8 +222,8 @@ void protocol_buffer_synchronize() {
|
||||
// is finished, single commands), a command that needs to wait for the motions in the buffer to
|
||||
// execute calls a buffer sync, or the planner buffer is full and ready to go.
|
||||
void protocol_auto_cycle_start() {
|
||||
if (plan_get_current_block() != NULL) { // Check if there are any blocks in the buffer.
|
||||
sys_cycleStart = true; // If so, execute them!
|
||||
if (plan_get_current_block() != NULL) { // Check if there are any blocks in the buffer.
|
||||
sys_cycleStart = true; // If so, execute them!
|
||||
}
|
||||
}
|
||||
|
||||
@@ -270,112 +270,110 @@ void protocol_exec_rt_system() {
|
||||
}
|
||||
sys_rt_exec_alarm = ExecAlarm::None;
|
||||
}
|
||||
ExecState rt_exec_state;
|
||||
rt_exec_state.value = sys_get_rt_exec_state().value; // Copy volatile sys_rt_exec_state.
|
||||
if (rt_exec_state.value != 0) { // Test if any bits are on
|
||||
// Execute system abort.
|
||||
if (rt_exec_state.bit.reset) {
|
||||
sys.abort = true; // Only place this is set true.
|
||||
return; // Nothing else to do but exit.
|
||||
}
|
||||
// Execute and serial print status
|
||||
if (rt_exec_state.bit.statusReport) {
|
||||
report_realtime_status(CLIENT_ALL);
|
||||
sys_statusReport = false;
|
||||
}
|
||||
// NOTE: Once hold is initiated, the system immediately enters a suspend state to block all
|
||||
// main program processes until either reset or resumed. This ensures a hold completes safely.
|
||||
if (rt_exec_state.bit.motionCancel || rt_exec_state.bit.feedHold || rt_exec_state.bit.safetyDoor || rt_exec_state.bit.sleep) {
|
||||
// State check for allowable states for hold methods.
|
||||
if (!(sys.state == State::Alarm || sys.state == State::CheckMode)) {
|
||||
// If in CYCLE or JOG states, immediately initiate a motion HOLD.
|
||||
if (sys.state == State::Cycle || sys.state == State::Jog) {
|
||||
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.
|
||||
sys.step_control = {};
|
||||
sys.step_control.executeHold = true; // Initiate suspend state with active flag.
|
||||
if (sys.state == State::Jog) { // Jog cancelled upon any hold event, except for sleeping.
|
||||
if (!rt_exec_state.bit.sleep) {
|
||||
sys.suspend.bit.jogCancel = true;
|
||||
}
|
||||
|
||||
// Execute system abort.
|
||||
if (sys_reset) {
|
||||
sys.abort = true; // Only place this is set true.
|
||||
return; // Nothing else to do but exit.
|
||||
}
|
||||
// Execute and serial print status
|
||||
if (sys_statusReport) {
|
||||
report_realtime_status(CLIENT_ALL);
|
||||
sys_statusReport = false;
|
||||
}
|
||||
// NOTE: Once hold is initiated, the system immediately enters a suspend state to block all
|
||||
// main program processes until either reset or resumed. This ensures a hold completes safely.
|
||||
if (sys_motionCancel || sys_feedHold || sys_safetyDoor || sys_sleep) {
|
||||
// State check for allowable states for hold methods.
|
||||
if (!(sys.state == State::Alarm || sys.state == State::CheckMode)) {
|
||||
// If in CYCLE or JOG states, immediately initiate a motion HOLD.
|
||||
if (sys.state == State::Cycle || sys.state == State::Jog) {
|
||||
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.
|
||||
sys.step_control = {};
|
||||
sys.step_control.executeHold = true; // Initiate suspend state with active flag.
|
||||
if (sys.state == State::Jog) { // Jog cancelled upon any hold event, except for sleeping.
|
||||
if (!sys_sleep) {
|
||||
sys.suspend.bit.jogCancel = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
// If IDLE, Grbl is not in motion. Simply indicate suspend state and hold is complete.
|
||||
if (sys.state == State::Idle) {
|
||||
sys.suspend.value = 0;
|
||||
sys.suspend.bit.holdComplete = true;
|
||||
}
|
||||
// If IDLE, Grbl is not in motion. Simply indicate suspend state and hold is complete.
|
||||
if (sys.state == State::Idle) {
|
||||
sys.suspend.value = 0;
|
||||
sys.suspend.bit.holdComplete = true;
|
||||
}
|
||||
// Execute and flag a motion cancel with deceleration and return to idle. Used primarily by probing cycle
|
||||
// to halt and cancel the remainder of the motion.
|
||||
if (sys_motionCancel) {
|
||||
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
|
||||
// to hold the CYCLE. Motion cancel is valid for a single planner block motion only, while jog cancel
|
||||
// will handle and clear multiple planner block motions.
|
||||
if (sys.state != State::Jog) {
|
||||
sys.suspend.bit.motionCancel = true; // NOTE: State is State::Cycle.
|
||||
}
|
||||
// Execute and flag a motion cancel with deceleration and return to idle. Used primarily by probing cycle
|
||||
// to halt and cancel the remainder of the motion.
|
||||
if (rt_exec_state.bit.motionCancel) {
|
||||
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
|
||||
// to hold the CYCLE. Motion cancel is valid for a single planner block motion only, while jog cancel
|
||||
// will handle and clear multiple planner block motions.
|
||||
if (sys.state != State::Jog) {
|
||||
sys.suspend.bit.motionCancel = true; // NOTE: State is State::Cycle.
|
||||
}
|
||||
sys_motionCancel = false;
|
||||
sys_motionCancel = false;
|
||||
}
|
||||
// Execute a feed hold with deceleration, if required. Then, suspend system.
|
||||
if (sys_feedHold) {
|
||||
// Block SAFETY_DOOR, JOG, and SLEEP states from changing to HOLD state.
|
||||
if (!(sys.state == State::SafetyDoor || sys.state == State::Jog || sys.state == State::Sleep)) {
|
||||
sys.state = State::Hold;
|
||||
}
|
||||
// Execute a feed hold with deceleration, if required. Then, suspend system.
|
||||
if (rt_exec_state.bit.feedHold) {
|
||||
// Block SAFETY_DOOR, JOG, and SLEEP states from changing to HOLD state.
|
||||
if (!(sys.state == State::SafetyDoor || sys.state == State::Jog || sys.state == State::Sleep)) {
|
||||
sys.state = State::Hold;
|
||||
}
|
||||
sys_feedHold = false;
|
||||
}
|
||||
// Execute a safety door stop with a feed hold and disable spindle/coolant.
|
||||
// NOTE: Safety door differs from feed holds by stopping everything no matter state, disables powered
|
||||
// devices (spindle/coolant), and blocks resuming until switch is re-engaged.
|
||||
if (rt_exec_state.bit.safetyDoor) {
|
||||
report_feedback_message(Message::SafetyDoorAjar);
|
||||
// If jogging, block safety door methods until jog cancel is complete. Just flag that it happened.
|
||||
if (!(sys.suspend.bit.jogCancel)) {
|
||||
// Check if the safety re-opened during a restore parking motion only. Ignore if
|
||||
// already retracting, parked or in sleep state.
|
||||
if (sys.state == State::SafetyDoor) {
|
||||
if (sys.suspend.bit.initiateRestore) { // Actively restoring
|
||||
sys_feedHold = false;
|
||||
}
|
||||
// Execute a safety door stop with a feed hold and disable spindle/coolant.
|
||||
// NOTE: Safety door differs from feed holds by stopping everything no matter state, disables powered
|
||||
// devices (spindle/coolant), and blocks resuming until switch is re-engaged.
|
||||
if (sys_safetyDoor) {
|
||||
report_feedback_message(Message::SafetyDoorAjar);
|
||||
// If jogging, block safety door methods until jog cancel is complete. Just flag that it happened.
|
||||
if (!(sys.suspend.bit.jogCancel)) {
|
||||
// Check if the safety re-opened during a restore parking motion only. Ignore if
|
||||
// already retracting, parked or in sleep state.
|
||||
if (sys.state == State::SafetyDoor) {
|
||||
if (sys.suspend.bit.initiateRestore) { // Actively restoring
|
||||
#ifdef PARKING_ENABLE
|
||||
// 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.
|
||||
sys.step_control = {};
|
||||
sys.step_control.executeHold = true;
|
||||
sys.step_control.executeSysMotion = true;
|
||||
sys.suspend.bit.holdComplete = false;
|
||||
} // else NO_MOTION is active.
|
||||
// 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.
|
||||
sys.step_control = {};
|
||||
sys.step_control.executeHold = true;
|
||||
sys.step_control.executeSysMotion = true;
|
||||
sys.suspend.bit.holdComplete = false;
|
||||
} // else NO_MOTION is active.
|
||||
#endif
|
||||
sys.suspend.bit.retractComplete = false;
|
||||
sys.suspend.bit.initiateRestore = false;
|
||||
sys.suspend.bit.restoreComplete = false;
|
||||
sys.suspend.bit.restartRetract = true;
|
||||
}
|
||||
sys.suspend.bit.retractComplete = false;
|
||||
sys.suspend.bit.initiateRestore = false;
|
||||
sys.suspend.bit.restoreComplete = false;
|
||||
sys.suspend.bit.restartRetract = true;
|
||||
}
|
||||
if (sys.state != State::Sleep) {
|
||||
sys.state = State::SafetyDoor;
|
||||
}
|
||||
sys_safetyDoor = false;
|
||||
}
|
||||
// NOTE: This flag doesn't change when the door closes, unlike sys.state. Ensures any parking motions
|
||||
// are executed if the door switch closes and the state returns to HOLD.
|
||||
sys.suspend.bit.safetyDoorAjar = true;
|
||||
if (sys.state != State::Sleep) {
|
||||
sys.state = State::SafetyDoor;
|
||||
}
|
||||
sys_safetyDoor = false;
|
||||
}
|
||||
}
|
||||
if (rt_exec_state.bit.sleep) {
|
||||
if (sys.state == State::Alarm) {
|
||||
sys.suspend.bit.retractComplete = true;
|
||||
sys.suspend.bit.holdComplete = true;
|
||||
}
|
||||
sys.state = State::Sleep;
|
||||
sys_sleep = false;
|
||||
// NOTE: This flag doesn't change when the door closes, unlike sys.state. Ensures any parking motions
|
||||
// are executed if the door switch closes and the state returns to HOLD.
|
||||
sys.suspend.bit.safetyDoorAjar = true;
|
||||
}
|
||||
}
|
||||
if (sys_sleep) {
|
||||
if (sys.state == State::Alarm) {
|
||||
sys.suspend.bit.retractComplete = true;
|
||||
sys.suspend.bit.holdComplete = true;
|
||||
}
|
||||
sys.state = State::Sleep;
|
||||
sys_sleep = false;
|
||||
}
|
||||
|
||||
// Execute a cycle start by starting the stepper interrupt to begin executing the blocks in queue.
|
||||
if (rt_exec_state.bit.cycleStart) {
|
||||
if (sys_cycleStart) {
|
||||
// Block if called at same time as the hold commands: feed hold, motion cancel, and safety door.
|
||||
// Ensures auto-cycle-start doesn't resume a hold without an explicit user-input.
|
||||
if (!(rt_exec_state.bit.feedHold || rt_exec_state.bit.motionCancel || rt_exec_state.bit.safetyDoor)) {
|
||||
if (!(sys_feedHold || sys_motionCancel || sys_safetyDoor)) {
|
||||
// Resume door state when parking motion has retracted and door has been closed.
|
||||
if (sys.state == State::SafetyDoor && !(sys.suspend.bit.safetyDoorAjar)) {
|
||||
if (sys.suspend.bit.restoreComplete) {
|
||||
@@ -410,7 +408,7 @@ void protocol_exec_rt_system() {
|
||||
}
|
||||
sys_cycleStart = false;
|
||||
}
|
||||
if (rt_exec_state.bit.cycleStop) {
|
||||
if (sys_cycleStop) {
|
||||
// Reinitializes the cycle plan and stepper system after a feed hold for a resume. Called by
|
||||
// realtime command execution in the main program, ensuring that the planner re-plans safely.
|
||||
// NOTE: Bresenham algorithm variables are still maintained through both the planner and stepper
|
||||
@@ -695,8 +693,8 @@ static void protocol_exec_rt_suspend() {
|
||||
}
|
||||
#endif
|
||||
if (!sys.suspend.bit.restartRetract) {
|
||||
sys.suspend.bit.restoreComplete = true;
|
||||
sys_cycleStart = true; // Set to resume program.
|
||||
sys.suspend.bit.restoreComplete = true;
|
||||
sys_cycleStart = true; // Set to resume program.
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@@ -26,17 +26,17 @@ system_t sys;
|
||||
int32_t sys_position[MAX_N_AXIS]; // Real-time machine (aka home) position vector in steps.
|
||||
int32_t sys_probe_position[MAX_N_AXIS]; // Last probe position in machine coordinates and steps.
|
||||
volatile Probe sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
|
||||
volatile ExecAlarm sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
|
||||
volatile ExecAlarm sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
|
||||
volatile ExecAccessory sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
|
||||
|
||||
volatile bool sys_statusReport; // For state transitions, instead of bitflag
|
||||
volatile bool sys_cycleStart;
|
||||
volatile bool sys_cycleStop;
|
||||
volatile bool sys_feedHold;
|
||||
volatile bool sys_reset;
|
||||
volatile bool sys_safetyDoor;
|
||||
volatile bool sys_motionCancel;
|
||||
volatile bool sys_sleep;
|
||||
volatile bool sys_statusReport; // For state transitions, instead of bitflag
|
||||
volatile bool sys_cycleStart;
|
||||
volatile bool sys_cycleStop;
|
||||
volatile bool sys_feedHold;
|
||||
volatile bool sys_reset;
|
||||
volatile bool sys_safetyDoor;
|
||||
volatile bool sys_motionCancel;
|
||||
volatile bool sys_sleep;
|
||||
|
||||
#ifdef DEBUG
|
||||
volatile bool sys_rt_exec_debug;
|
||||
@@ -343,20 +343,6 @@ uint8_t sys_calc_pwm_precision(uint32_t freq) {
|
||||
return precision - 1;
|
||||
}
|
||||
|
||||
ExecState sys_get_rt_exec_state() {
|
||||
ExecState result;
|
||||
result.value = 0;
|
||||
result.bit.statusReport = sys_statusReport;
|
||||
result.bit.cycleStart = sys_cycleStart;
|
||||
result.bit.cycleStop = sys_cycleStop;
|
||||
result.bit.feedHold = sys_feedHold;
|
||||
result.bit.reset = sys_reset;
|
||||
result.bit.safetyDoor = sys_safetyDoor;
|
||||
result.bit.motionCancel = sys_motionCancel;
|
||||
result.bit.sleep = sys_sleep;
|
||||
return result;
|
||||
}
|
||||
|
||||
void __attribute__((weak)) user_defined_macro(uint8_t index) {
|
||||
// must be in Idle
|
||||
if (sys.state != State::Idle) {
|
||||
|
@@ -139,14 +139,14 @@ extern volatile Percent sys_rt_s_override; // Spindle overri
|
||||
|
||||
// System executor bits. Used internally by realtime protocol as realtime command flags,
|
||||
// which notifies the main program to execute the specified realtime command asynchronously.
|
||||
extern volatile bool sys_statusReport;
|
||||
extern volatile bool sys_cycleStart;
|
||||
extern volatile bool sys_cycleStop;
|
||||
extern volatile bool sys_feedHold;
|
||||
extern volatile bool sys_reset;
|
||||
extern volatile bool sys_safetyDoor;
|
||||
extern volatile bool sys_motionCancel;
|
||||
extern volatile bool sys_sleep;
|
||||
extern volatile bool sys_statusReport;
|
||||
extern volatile bool sys_cycleStart;
|
||||
extern volatile bool sys_cycleStop;
|
||||
extern volatile bool sys_feedHold;
|
||||
extern volatile bool sys_reset;
|
||||
extern volatile bool sys_safetyDoor;
|
||||
extern volatile bool sys_motionCancel;
|
||||
extern volatile bool sys_sleep;
|
||||
|
||||
#ifdef DEBUG
|
||||
extern volatile bool sys_rt_exec_debug;
|
||||
@@ -185,5 +185,3 @@ bool sys_pwm_control(uint8_t io_num_mask, float duty, bool synchronized);
|
||||
|
||||
int8_t sys_get_next_PWM_chan_num();
|
||||
uint8_t sys_calc_pwm_precision(uint32_t freq);
|
||||
|
||||
ExecState sys_get_rt_exec_state();
|
||||
|
Reference in New Issue
Block a user