Add loose soft endstop state, apply to UBL fine-tune (#19681)
Co-authored-by: Scott Lahteine <thinkyhead@users.noreply.github.com>
This commit is contained in:
parent
48a24202ef
commit
ea65e10dc7
|
@ -1009,6 +1009,8 @@
|
|||
|
||||
lcd_mesh_edit_setup(new_z);
|
||||
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
|
||||
do {
|
||||
idle();
|
||||
new_z = lcd_mesh_edit();
|
||||
|
@ -1016,6 +1018,8 @@
|
|||
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
|
||||
} while (!ui.button_pressed());
|
||||
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
|
||||
if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status
|
||||
|
||||
if (click_and_hold(abort_fine_tune)) break; // Button held down? Abort editing
|
||||
|
|
|
@ -201,10 +201,6 @@ G29_TYPE GcodeSuite::G29() {
|
|||
ABL_VAR int abl_probe_index;
|
||||
#endif
|
||||
|
||||
#if BOTH(HAS_SOFTWARE_ENDSTOPS, PROBE_MANUALLY)
|
||||
ABL_VAR bool saved_soft_endstops_state = true;
|
||||
#endif
|
||||
|
||||
#if ABL_GRID
|
||||
|
||||
#if ENABLED(PROBE_MANUALLY)
|
||||
|
@ -461,7 +457,7 @@ G29_TYPE GcodeSuite::G29() {
|
|||
// Abort current G29 procedure, go back to idle state
|
||||
if (seenA && g29_in_progress) {
|
||||
SERIAL_ECHOLNPGM("Manual G29 aborted");
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
set_bed_leveling_enabled(abl_should_enable);
|
||||
g29_in_progress = false;
|
||||
TERN_(LCD_BED_LEVELING, ui.wait_for_move = false);
|
||||
|
@ -482,7 +478,7 @@ G29_TYPE GcodeSuite::G29() {
|
|||
|
||||
if (abl_probe_index == 0) {
|
||||
// For the initial G29 S2 save software endstop state
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, saved_soft_endstops_state = soft_endstops_enabled);
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
// Move close to the bed before the first point
|
||||
do_blocking_move_to_z(0);
|
||||
}
|
||||
|
@ -552,14 +548,14 @@ G29_TYPE GcodeSuite::G29() {
|
|||
_manual_goto_xy(probePos); // Can be used here too!
|
||||
// Disable software endstops to allow manual adjustment
|
||||
// If G29 is not completed, they will not be re-enabled
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false);
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
G29_RETURN(false);
|
||||
}
|
||||
else {
|
||||
// Leveling done! Fall through to G29 finishing code below
|
||||
SERIAL_ECHOLNPGM("Grid probing done.");
|
||||
// Re-enable software endstops, if needed
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
}
|
||||
|
||||
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
|
||||
|
@ -570,7 +566,7 @@ G29_TYPE GcodeSuite::G29() {
|
|||
_manual_goto_xy(probePos);
|
||||
// Disable software endstops to allow manual adjustment
|
||||
// If G29 is not completed, they will not be re-enabled
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = false);
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
G29_RETURN(false);
|
||||
}
|
||||
else {
|
||||
|
@ -578,7 +574,7 @@ G29_TYPE GcodeSuite::G29() {
|
|||
SERIAL_ECHOLNPGM("3-point probing done.");
|
||||
|
||||
// Re-enable software endstops, if needed
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
|
||||
if (!dryrun) {
|
||||
vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal();
|
||||
|
|
|
@ -61,7 +61,6 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM("
|
|||
void GcodeSuite::G29() {
|
||||
|
||||
static int mbl_probe_index = -1;
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, static bool saved_soft_endstops_state);
|
||||
|
||||
MeshLevelingState state = (MeshLevelingState)parser.byteval('S', (int8_t)MeshReport);
|
||||
if (!WITHIN(state, 0, 5)) {
|
||||
|
@ -98,26 +97,19 @@ void GcodeSuite::G29() {
|
|||
}
|
||||
// For each G29 S2...
|
||||
if (mbl_probe_index == 0) {
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
// For the initial G29 S2 save software endstop state
|
||||
saved_soft_endstops_state = soft_endstops_enabled;
|
||||
#endif
|
||||
// Move close to the bed before the first point
|
||||
do_blocking_move_to_z(0);
|
||||
}
|
||||
else {
|
||||
// Save Z for the previous mesh position
|
||||
mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z);
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = saved_soft_endstops_state);
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
}
|
||||
// If there's another point to sample, move there with optional lift.
|
||||
if (mbl_probe_index < GRID_MAX_POINTS) {
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
// Disable software endstops to allow manual adjustment
|
||||
// If G29 is not completed, they will not be re-enabled
|
||||
soft_endstops_enabled = false;
|
||||
#endif
|
||||
|
||||
// If G29 is left hanging without completion they won't be re-enabled!
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
mbl.zigzag(mbl_probe_index++, ix, iy);
|
||||
_manual_goto_xy({ mbl.index_to_xpos[ix], mbl.index_to_ypos[iy] });
|
||||
}
|
||||
|
|
|
@ -222,8 +222,9 @@ void GcodeSuite::G28() {
|
|||
return;
|
||||
}
|
||||
|
||||
// Wait for planner moves to finish!
|
||||
planner.synchronize();
|
||||
planner.synchronize(); // Wait for planner moves to finish!
|
||||
|
||||
SET_SOFT_ENDSTOP_LOOSE(false); // Reset a leftover 'loose' motion state
|
||||
|
||||
// Disable the leveling matrix before homing
|
||||
#if HAS_LEVELING
|
||||
|
|
|
@ -40,7 +40,7 @@ void GcodeSuite::G34() {
|
|||
|
||||
if (homing_needed()) return;
|
||||
|
||||
TEMPORARY_SOFT_ENDSTOP_STATE(false);
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
TEMPORARY_BED_LEVELING_STATE(false);
|
||||
TemporaryGlobalEndstopsState unlock_z(false);
|
||||
|
||||
|
@ -148,6 +148,8 @@ void GcodeSuite::G34() {
|
|||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Running Post Commands");
|
||||
gcode.process_subcommands_now_P(PSTR(GANTRY_CALIBRATION_COMMANDS_POST));
|
||||
#endif
|
||||
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
}
|
||||
|
||||
#endif // MECHANICAL_GANTRY_CALIBRATION
|
||||
|
|
|
@ -581,13 +581,12 @@ void GcodeSuite::G425() {
|
|||
GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_PRE));
|
||||
#endif
|
||||
|
||||
TEMPORARY_SOFT_ENDSTOP_STATE(false);
|
||||
TEMPORARY_BED_LEVELING_STATE(false);
|
||||
|
||||
if (homing_needed_error()) return;
|
||||
|
||||
measurements_t m;
|
||||
TEMPORARY_BED_LEVELING_STATE(false);
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
|
||||
measurements_t m;
|
||||
float uncertainty = parser.seenval('U') ? parser.value_float() : CALIBRATION_MEASUREMENT_UNCERTAIN;
|
||||
|
||||
if (parser.seen('B'))
|
||||
|
@ -612,6 +611,8 @@ void GcodeSuite::G425() {
|
|||
else
|
||||
calibrate_all();
|
||||
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
|
||||
#ifdef CALIBRATION_SCRIPT_POST
|
||||
GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_POST));
|
||||
#endif
|
||||
|
|
|
@ -37,8 +37,8 @@ void GcodeSuite::M211() {
|
|||
l_soft_max = soft_endstop.max.asLogical();
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM(STR_SOFT_ENDSTOPS);
|
||||
if (parser.seen('S')) soft_endstops_enabled = parser.value_bool();
|
||||
serialprint_onoff(soft_endstops_enabled);
|
||||
if (parser.seen('S')) soft_endstop._enabled = parser.value_bool();
|
||||
serialprint_onoff(soft_endstop._enabled);
|
||||
print_xyz(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" "));
|
||||
print_xyz(l_soft_max, PSTR(STR_SOFT_MAX));
|
||||
}
|
||||
|
|
|
@ -70,9 +70,11 @@ void GcodeSuite::G12() {
|
|||
TEMPORARY_BED_LEVELING_STATE(!TEST(cleans, Z_AXIS) && planner.leveling_active);
|
||||
#endif
|
||||
|
||||
TEMPORARY_SOFT_ENDSTOP_STATE(parser.boolval('E'));
|
||||
SET_SOFT_ENDSTOP_LOOSE(!parser.boolval('E'));
|
||||
|
||||
nozzle.clean(pattern, strokes, radius, objects, cleans);
|
||||
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
}
|
||||
|
||||
#endif // NOZZLE_CLEAN_FEATURE
|
||||
|
|
|
@ -305,27 +305,9 @@ namespace ExtUI {
|
|||
}
|
||||
|
||||
void setAxisPosition_mm(const float position, const axis_t axis, const feedRate_t feedrate/*=0*/) {
|
||||
// Start with no limits to movement
|
||||
float min = current_position[axis] - 1000,
|
||||
max = current_position[axis] + 1000;
|
||||
|
||||
// Limit to software endstops, if enabled
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
if (soft_endstops_enabled) switch (axis) {
|
||||
case X_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_X, min = soft_endstop.min.x);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_X, max = soft_endstop.max.x);
|
||||
break;
|
||||
case Y_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Y, min = soft_endstop.min.y);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Y, max = soft_endstop.max.y);
|
||||
break;
|
||||
case Z_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Z, min = soft_endstop.min.z);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Z, max = soft_endstop.max.z);
|
||||
default: break;
|
||||
}
|
||||
#endif // HAS_SOFTWARE_ENDSTOPS
|
||||
// Get motion limit from software endstops, if any
|
||||
float min, max;
|
||||
soft_endstop.get_manual_axis_limits((AxisEnum)axis, min, max);
|
||||
|
||||
// Delta limits XY based on the current offset from center
|
||||
// This assumes the center is 0,0
|
||||
|
@ -389,8 +371,8 @@ namespace ExtUI {
|
|||
}
|
||||
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
bool getSoftEndstopState() { return soft_endstops_enabled; }
|
||||
void setSoftEndstopState(const bool value) { soft_endstops_enabled = value; }
|
||||
bool getSoftEndstopState() { return soft_endstop._enabled; }
|
||||
void setSoftEndstopState(const bool value) { soft_endstop._enabled = value; }
|
||||
#endif
|
||||
|
||||
#if HAS_TRINAMIC_CONFIG
|
||||
|
|
|
@ -57,28 +57,9 @@
|
|||
static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) {
|
||||
if (ui.use_click()) return ui.goto_previous_screen_no_defer();
|
||||
if (ui.encoderPosition && !ui.manual_move.processing) {
|
||||
|
||||
// Start with no limits to movement
|
||||
float min = current_position[axis] - 1000,
|
||||
max = current_position[axis] + 1000;
|
||||
|
||||
// Limit to software endstops, if enabled
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
if (soft_endstops_enabled) switch (axis) {
|
||||
case X_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_X, min = soft_endstop.min.x);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_X, max = soft_endstop.max.x);
|
||||
break;
|
||||
case Y_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Y, min = soft_endstop.min.y);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Y, max = soft_endstop.max.y);
|
||||
break;
|
||||
case Z_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Z, min = soft_endstop.min.z);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Z, max = soft_endstop.max.z);
|
||||
default: break;
|
||||
}
|
||||
#endif // HAS_SOFTWARE_ENDSTOPS
|
||||
// Get motion limit from software endstops, if any
|
||||
float min, max;
|
||||
soft_endstop.get_manual_axis_limits(axis, min, max);
|
||||
|
||||
// Delta limits XY based on the current offset from center
|
||||
// This assumes the center is 0,0
|
||||
|
@ -238,7 +219,7 @@ void menu_move() {
|
|||
BACK_ITEM(MSG_MOTION);
|
||||
|
||||
#if BOTH(HAS_SOFTWARE_ENDSTOPS, SOFT_ENDSTOPS_MENU_ITEM)
|
||||
EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstops_enabled);
|
||||
EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstop._enabled);
|
||||
#endif
|
||||
|
||||
if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) {
|
||||
|
|
|
@ -48,16 +48,12 @@
|
|||
float z_offset_backup, calculated_z_offset;
|
||||
|
||||
TERN_(HAS_LEVELING, bool leveling_was_active);
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, bool store_soft_endstops_enabled);
|
||||
|
||||
void prepare_for_calibration() {
|
||||
z_offset_backup = probe.offset.z;
|
||||
|
||||
// Disable soft endstops for free Z movement
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
store_soft_endstops_enabled = soft_endstops_enabled;
|
||||
soft_endstops_enabled = false;
|
||||
#endif
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
|
||||
// Disable leveling for raw planner motion
|
||||
#if HAS_LEVELING
|
||||
|
@ -68,7 +64,7 @@ void prepare_for_calibration() {
|
|||
|
||||
void set_offset_and_go_back(const float &z) {
|
||||
probe.offset.z = z;
|
||||
TERN_(HAS_SOFTWARE_ENDSTOPS, soft_endstops_enabled = store_soft_endstops_enabled);
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active));
|
||||
ui.goto_previous_screen_no_defer();
|
||||
}
|
||||
|
|
|
@ -813,27 +813,9 @@ static void moveAxis(AxisEnum axis, const int8_t direction) {
|
|||
}
|
||||
|
||||
if (!ui.manual_move.processing) {
|
||||
// Start with no limits to movement
|
||||
float min = current_position[axis] - 1000,
|
||||
max = current_position[axis] + 1000;
|
||||
|
||||
// Limit to software endstops, if enabled
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
if (soft_endstops_enabled) switch (axis) {
|
||||
case X_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_X, min = soft_endstop.min.x);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_X, max = soft_endstop.max.x);
|
||||
break;
|
||||
case Y_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Y, min = soft_endstop.min.y);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Y, max = soft_endstop.max.y);
|
||||
break;
|
||||
case Z_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Z, min = soft_endstop.min.z);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Z, max = soft_endstop.max.z);
|
||||
default: break;
|
||||
}
|
||||
#endif // HAS_SOFTWARE_ENDSTOPS
|
||||
// Get motion limit from software endstops, if any
|
||||
float min, max;
|
||||
soft_endstop.get_manual_axis_limits(axis, min, max);
|
||||
|
||||
// Delta limits XY based on the current offset from center
|
||||
// This assumes the center is 0,0
|
||||
|
|
|
@ -161,7 +161,7 @@ Nozzle nozzle;
|
|||
LIMIT( end[arrPos].A, soft_endstop.min.A, soft_endstop.max.A); \
|
||||
}while(0)
|
||||
|
||||
if (soft_endstops_enabled) {
|
||||
if (soft_endstop.enabled()) {
|
||||
|
||||
LIMIT_AXIS(x);
|
||||
LIMIT_AXIS(y);
|
||||
|
|
|
@ -534,12 +534,11 @@ void restore_feedrate_and_scaling() {
|
|||
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
|
||||
bool soft_endstops_enabled = true;
|
||||
|
||||
// Software Endstops are based on the configured limits.
|
||||
axis_limits_t soft_endstop = {
|
||||
soft_endstops_t soft_endstop = {
|
||||
{ X_MIN_POS, Y_MIN_POS, Z_MIN_POS },
|
||||
{ X_MAX_POS, Y_MAX_POS, Z_MAX_POS }
|
||||
{ X_MAX_POS, Y_MAX_POS, Z_MAX_POS },
|
||||
{ true, false }
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -636,7 +635,7 @@ void restore_feedrate_and_scaling() {
|
|||
*/
|
||||
void apply_motion_limits(xyz_pos_t &target) {
|
||||
|
||||
if (!soft_endstops_enabled) return;
|
||||
if (!soft_endstop._enabled) return;
|
||||
|
||||
#if IS_KINEMATIC
|
||||
|
||||
|
@ -688,7 +687,11 @@ void restore_feedrate_and_scaling() {
|
|||
}
|
||||
}
|
||||
|
||||
#endif // HAS_SOFTWARE_ENDSTOPS
|
||||
#else // !HAS_SOFTWARE_ENDSTOPS
|
||||
|
||||
soft_endstops_t soft_endstop;
|
||||
|
||||
#endif // !HAS_SOFTWARE_ENDSTOPS
|
||||
|
||||
#if !UBL_SEGMENTED
|
||||
|
||||
|
|
|
@ -148,26 +148,61 @@ inline float home_bump_mm(const AxisEnum axis) {
|
|||
constexpr xyz_pos_t hotend_offset[1] = { { 0 } };
|
||||
#endif
|
||||
|
||||
typedef struct { xyz_pos_t min, max; } axis_limits_t;
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
extern bool soft_endstops_enabled;
|
||||
extern axis_limits_t soft_endstop;
|
||||
|
||||
typedef struct {
|
||||
xyz_pos_t min, max;
|
||||
struct {
|
||||
bool _enabled:1;
|
||||
bool _loose:1;
|
||||
};
|
||||
bool enabled() { return _enabled && !_loose; }
|
||||
void get_manual_axis_limits(const AxisEnum axis, float &amin, float &amax) {
|
||||
amin = -100000; amax = 100000; // "No limits"
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
if (enabled()) switch (axis) {
|
||||
case X_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x);
|
||||
break;
|
||||
case Y_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y);
|
||||
break;
|
||||
case Z_AXIS:
|
||||
TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z);
|
||||
TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z);
|
||||
default: break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
} soft_endstops_t;
|
||||
|
||||
extern soft_endstops_t soft_endstop;
|
||||
void apply_motion_limits(xyz_pos_t &target);
|
||||
void update_software_endstops(const AxisEnum axis
|
||||
#if HAS_HOTEND_OFFSET
|
||||
, const uint8_t old_tool_index=0, const uint8_t new_tool_index=0
|
||||
#endif
|
||||
);
|
||||
#define TEMPORARY_SOFT_ENDSTOP_STATE(enable) REMEMBER(tes, soft_endstops_enabled, enable);
|
||||
#else
|
||||
constexpr bool soft_endstops_enabled = false;
|
||||
//constexpr axis_limits_t soft_endstop = {
|
||||
// { X_MIN_POS, Y_MIN_POS, Z_MIN_POS },
|
||||
// { X_MAX_POS, Y_MAX_POS, Z_MAX_POS } };
|
||||
#define SET_SOFT_ENDSTOP_LOOSE(loose) (soft_endstop._loose = loose)
|
||||
|
||||
#else // !HAS_SOFTWARE_ENDSTOPS
|
||||
|
||||
typedef struct {
|
||||
bool enabled() { return false; }
|
||||
void get_manual_axis_limits(const AxisEnum axis, float &amin, float &amax) {
|
||||
// No limits
|
||||
amin = current_position[axis] - 1000;
|
||||
amax = current_position[axis] + 1000;
|
||||
}
|
||||
} soft_endstops_t;
|
||||
extern soft_endstops_t soft_endstop;
|
||||
#define apply_motion_limits(V) NOOP
|
||||
#define update_software_endstops(...) NOOP
|
||||
#define TEMPORARY_SOFT_ENDSTOP_STATE(...) NOOP
|
||||
#endif
|
||||
#define SET_SOFT_ENDSTOP_LOOSE() NOOP
|
||||
|
||||
#endif // !HAS_SOFTWARE_ENDSTOPS
|
||||
|
||||
void report_real_position();
|
||||
void report_current_position();
|
||||
|
|
|
@ -1017,14 +1017,10 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) {
|
|||
// Raise by a configured distance to avoid workpiece, except with
|
||||
// SWITCHING_NOZZLE_TWO_SERVOS, as both nozzles will lift instead.
|
||||
if (!no_move) {
|
||||
#if HAS_SOFTWARE_ENDSTOPS
|
||||
const float maxz = _MIN(soft_endstop.max.z, Z_MAX_POS);
|
||||
#else
|
||||
constexpr float maxz = Z_MAX_POS;
|
||||
#endif
|
||||
const float newz = current_position.z + _MAX(-diff.z, 0.0);
|
||||
|
||||
// Check if Z has space to compensate at least z_offset, and if not, just abort now
|
||||
const float newz = current_position.z + _MAX(-diff.z, 0.0);
|
||||
const float maxz = _MIN(TERN(HAS_SOFTWARE_ENDSTOPS, soft_endstop.max.z, Z_MAX_POS), Z_MAX_POS);
|
||||
if (newz > maxz) return;
|
||||
|
||||
current_position.z = _MIN(newz + toolchange_settings.z_raise, maxz);
|
||||
|
|
Loading…
Reference in a new issue