mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 03:13:25 +02:00
Created Probe Protection Feature
This commit is contained in:
@@ -391,8 +391,10 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
|
|||||||
return GCUpdatePos::None; // Return if system reset has been issued.
|
return GCUpdatePos::None; // Return if system reset has been issued.
|
||||||
}
|
}
|
||||||
|
|
||||||
|
probe_set_protection(false);
|
||||||
|
|
||||||
#ifdef USE_I2S_STEPS
|
#ifdef USE_I2S_STEPS
|
||||||
stepper_id_t save_stepper = current_stepper; /* remember the stepper */
|
stepper_id_t save_stepper = current_stepper; /* remember the stepper */
|
||||||
#endif
|
#endif
|
||||||
// Switch stepper mode to the I2S static (realtime mode)
|
// Switch stepper mode to the I2S static (realtime mode)
|
||||||
BACKUP_STEPPER(save_stepper);
|
BACKUP_STEPPER(save_stepper);
|
||||||
@@ -410,8 +412,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
|
|||||||
RESTORE_STEPPER(save_stepper); // Switch the stepper mode to the previous mode
|
RESTORE_STEPPER(save_stepper); // Switch the stepper mode to the previous mode
|
||||||
return GCUpdatePos::None; // Nothing else to do but bail.
|
return GCUpdatePos::None; // Nothing else to do but bail.
|
||||||
}
|
}
|
||||||
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Found");
|
|
||||||
mc_line_kins(target, pl_data, gc_state.position);
|
mc_line_kins(target, pl_data, gc_state.position);
|
||||||
// Activate the probing state monitor in the stepper module.
|
// Activate the probing state monitor in the stepper module.
|
||||||
sys_probe_state = Probe::Active;
|
sys_probe_state = Probe::Active;
|
||||||
@@ -442,9 +443,11 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
|
|||||||
sys_probe_state = Probe::Off; // Ensure probe state monitor is disabled.
|
sys_probe_state = Probe::Off; // Ensure probe state monitor is disabled.
|
||||||
protocol_execute_realtime(); // Check and execute run-time commands
|
protocol_execute_realtime(); // Check and execute run-time commands
|
||||||
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
||||||
st_reset(); // Reset step segment buffer.
|
st_reset(); // Reset step segment buffer.
|
||||||
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
||||||
plan_sync_position(); // Sync planner position to current machine position.
|
plan_sync_position(); // Sync planner position to current machine position.
|
||||||
|
user_probe_notification(); // weak user can supply to get notification
|
||||||
|
probe_set_protection(true);
|
||||||
#ifdef MESSAGE_PROBE_COORDINATES
|
#ifdef MESSAGE_PROBE_COORDINATES
|
||||||
// All done! Output the probe position as message.
|
// All done! Output the probe position as message.
|
||||||
report_probe_parameters(CLIENT_ALL);
|
report_probe_parameters(CLIENT_ALL);
|
||||||
@@ -541,3 +544,6 @@ void mc_reset() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
__attribute__((weak)) void user_probe_begin() {} // called before probing starts
|
||||||
|
__attribute__((weak)) void user_probe_notification() {} // called after probing complete
|
@@ -77,3 +77,6 @@ enum class SquaringMode : uint8_t {
|
|||||||
};
|
};
|
||||||
|
|
||||||
extern SquaringMode ganged_mode;
|
extern SquaringMode ganged_mode;
|
||||||
|
|
||||||
|
void user_probe_begin(); // weak. User to supply if needed
|
||||||
|
void user_probe_notification(); // weak. User to supply if needed
|
@@ -26,6 +26,25 @@
|
|||||||
// Inverts the probe pin state depending on user settings and probing cycle mode.
|
// Inverts the probe pin state depending on user settings and probing cycle mode.
|
||||||
static bool is_probe_away;
|
static bool is_probe_away;
|
||||||
|
|
||||||
|
void IRAM_ATTR isr_probe_protect() {
|
||||||
|
if (sys.state == State::Cycle || sys.state == State::Jog) {
|
||||||
|
if (probe_get_state()) {
|
||||||
|
switch (static_cast<ProbeProtection>(probe_protection->get())) {
|
||||||
|
case ProbeProtection::RESET:
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Probe contact:Reset");
|
||||||
|
mc_reset();
|
||||||
|
break;
|
||||||
|
case ProbeProtection::FEEDHOLD:
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Probe contact:Feedhold");
|
||||||
|
sys_rt_exec_state.bit.feedHold = true;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Probe pin initialization routine.
|
// Probe pin initialization routine.
|
||||||
void probe_init() {
|
void probe_init() {
|
||||||
static bool show_init_msg = true; // used to show message only once.
|
static bool show_init_msg = true; // used to show message only once.
|
||||||
@@ -37,6 +56,8 @@ void probe_init() {
|
|||||||
pinMode(PROBE_PIN, INPUT_PULLUP); // Enable internal pull-up resistors. Normal high operation.
|
pinMode(PROBE_PIN, INPUT_PULLUP); // Enable internal pull-up resistors. Normal high operation.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
probe_set_protection(true);
|
||||||
|
|
||||||
if (show_init_msg) {
|
if (show_init_msg) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Probe on pin %s", pinName(PROBE_PIN).c_str());
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Probe on pin %s", pinName(PROBE_PIN).c_str());
|
||||||
show_init_msg = false;
|
show_init_msg = false;
|
||||||
@@ -63,3 +84,17 @@ void probe_state_monitor() {
|
|||||||
sys_rt_exec_state.bit.motionCancel = true;
|
sys_rt_exec_state.bit.motionCancel = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Probe protection optionally motitors the probe for contact when the probe cycle is not running
|
||||||
|
// This can stop motion to prevent damaging the probe when it is accidentally crashed into sometihng
|
||||||
|
void probe_set_protection(bool on) {
|
||||||
|
if (PROBE_PIN != UNDEFINED_PIN) {
|
||||||
|
if (on) {
|
||||||
|
if (static_cast<ProbeProtection>(probe_protection->get()) != ProbeProtection::OFF) {
|
||||||
|
attachInterrupt(PROBE_PIN, isr_probe_protect, CHANGE);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
detachInterrupt(PROBE_PIN);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@@ -29,6 +29,16 @@ enum class Probe : uint8_t {
|
|||||||
Active = 1, // Actively watching the input pin.
|
Active = 1, // Actively watching the input pin.
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum class ProbeProtection : int8_t {
|
||||||
|
OFF = 0,
|
||||||
|
RESET,
|
||||||
|
FEEDHOLD,
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#define DEFAULT_PROBE_PROTECTION ProbeProtection::OFF
|
||||||
|
|
||||||
// Probe pin initialization routine.
|
// Probe pin initialization routine.
|
||||||
void probe_init();
|
void probe_init();
|
||||||
|
|
||||||
@@ -41,3 +51,6 @@ bool probe_get_state();
|
|||||||
// Monitors probe pin state and records the system position when detected. Called by the
|
// Monitors probe pin state and records the system position when detected. Called by the
|
||||||
// stepper ISR per ISR tick.
|
// stepper ISR per ISR tick.
|
||||||
void probe_state_monitor();
|
void probe_state_monitor();
|
||||||
|
|
||||||
|
//
|
||||||
|
void probe_set_protection(bool on);
|
||||||
|
@@ -22,7 +22,10 @@ AxisMaskSetting* stallguard_debug_mask;
|
|||||||
|
|
||||||
FlagSetting* step_enable_invert;
|
FlagSetting* step_enable_invert;
|
||||||
FlagSetting* limit_invert;
|
FlagSetting* limit_invert;
|
||||||
|
|
||||||
FlagSetting* probe_invert;
|
FlagSetting* probe_invert;
|
||||||
|
EnumSetting* probe_protection;
|
||||||
|
|
||||||
FlagSetting* report_inches;
|
FlagSetting* report_inches;
|
||||||
FlagSetting* soft_limits;
|
FlagSetting* soft_limits;
|
||||||
// TODO Settings - need to check for HOMING_ENABLE
|
// TODO Settings - need to check for HOMING_ENABLE
|
||||||
@@ -87,6 +90,14 @@ enum_opt_t messageLevels = {
|
|||||||
// clang-format on
|
// clang-format on
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum_opt_t probeProtectionTypes = {
|
||||||
|
// clang-format off
|
||||||
|
{ "Off", int8_t(ProbeProtection::OFF) },
|
||||||
|
{ "Reset", int8_t(ProbeProtection::RESET) },
|
||||||
|
{ "FeedHold", int8_t(ProbeProtection::FEEDHOLD) },
|
||||||
|
// clang-format on
|
||||||
|
};
|
||||||
|
|
||||||
AxisSettings* x_axis_settings;
|
AxisSettings* x_axis_settings;
|
||||||
AxisSettings* y_axis_settings;
|
AxisSettings* y_axis_settings;
|
||||||
AxisSettings* z_axis_settings;
|
AxisSettings* z_axis_settings;
|
||||||
@@ -202,6 +213,13 @@ static bool postMotorSetting(char* value) {
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static bool postProbeChange(char* value) {
|
||||||
|
if (!value) {
|
||||||
|
probe_set_protection(true);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
static bool checkSpindleChange(char* val) {
|
static bool checkSpindleChange(char* val) {
|
||||||
if (!val) {
|
if (!val) {
|
||||||
// if not in disable (M5) ...
|
// if not in disable (M5) ...
|
||||||
@@ -393,7 +411,10 @@ void make_settings() {
|
|||||||
junction_deviation = new FloatSetting(GRBL, WG, "11", "GCode/JunctionDeviation", DEFAULT_JUNCTION_DEVIATION, 0, 10);
|
junction_deviation = new FloatSetting(GRBL, WG, "11", "GCode/JunctionDeviation", DEFAULT_JUNCTION_DEVIATION, 0, 10);
|
||||||
status_mask = new IntSetting(GRBL, WG, "10", "Report/Status", DEFAULT_STATUS_REPORT_MASK, 0, 3);
|
status_mask = new IntSetting(GRBL, WG, "10", "Report/Status", DEFAULT_STATUS_REPORT_MASK, 0, 3);
|
||||||
|
|
||||||
probe_invert = new FlagSetting(GRBL, WG, "6", "Probe/Invert", DEFAULT_INVERT_PROBE_PIN);
|
probe_invert = new FlagSetting(GRBL, WG, "6", "Probe/Invert", DEFAULT_INVERT_PROBE_PIN);
|
||||||
|
probe_protection = new EnumSetting(
|
||||||
|
NULL, EXTENDED, WG, NULL, "Probe/Protection", static_cast<int8_t>(DEFAULT_PROBE_PROTECTION), &probeProtectionTypes, postProbeChange);
|
||||||
|
|
||||||
limit_invert = new FlagSetting(GRBL, WG, "5", "Limits/Invert", DEFAULT_INVERT_LIMIT_PINS);
|
limit_invert = new FlagSetting(GRBL, WG, "5", "Limits/Invert", DEFAULT_INVERT_LIMIT_PINS);
|
||||||
step_enable_invert = new FlagSetting(GRBL, WG, "4", "Stepper/EnableInvert", DEFAULT_INVERT_ST_ENABLE);
|
step_enable_invert = new FlagSetting(GRBL, WG, "4", "Stepper/EnableInvert", DEFAULT_INVERT_ST_ENABLE);
|
||||||
dir_invert_mask = new AxisMaskSetting(GRBL, WG, "3", "Stepper/DirInvert", DEFAULT_DIRECTION_INVERT_MASK, postMotorSetting);
|
dir_invert_mask = new AxisMaskSetting(GRBL, WG, "3", "Stepper/DirInvert", DEFAULT_DIRECTION_INVERT_MASK, postMotorSetting);
|
||||||
|
@@ -30,6 +30,7 @@ extern AxisMaskSetting* homing_cycle[MAX_N_AXIS];
|
|||||||
extern FlagSetting* step_enable_invert;
|
extern FlagSetting* step_enable_invert;
|
||||||
extern FlagSetting* limit_invert;
|
extern FlagSetting* limit_invert;
|
||||||
extern FlagSetting* probe_invert;
|
extern FlagSetting* probe_invert;
|
||||||
|
extern EnumSetting* probe_protection;
|
||||||
extern FlagSetting* report_inches;
|
extern FlagSetting* report_inches;
|
||||||
extern FlagSetting* soft_limits;
|
extern FlagSetting* soft_limits;
|
||||||
extern FlagSetting* hard_limits;
|
extern FlagSetting* hard_limits;
|
||||||
|
Reference in New Issue
Block a user