From bfe223e1209af4e50917e752124c7215a4c38953 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 3 May 2018 20:51:10 -0500 Subject: [PATCH] Adjust usage of stepper.synchronize --- Marlin/src/feature/I2CPositionEncoder.cpp | 10 +++++----- Marlin/src/feature/pause.cpp | 8 ++++---- Marlin/src/gcode/bedlevel/G26.cpp | 10 +--------- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- Marlin/src/gcode/control/M80_M81.cpp | 1 - Marlin/src/gcode/host/M114.cpp | 4 ++-- Marlin/src/gcode/lcd/M0_M1.cpp | 4 ++-- Marlin/src/module/motion.cpp | 8 ++++---- 8 files changed, 19 insertions(+), 28 deletions(-) diff --git a/Marlin/src/feature/I2CPositionEncoder.cpp b/Marlin/src/feature/I2CPositionEncoder.cpp index 7c80ff3a3..9d7e4bddb 100644 --- a/Marlin/src/feature/I2CPositionEncoder.cpp +++ b/Marlin/src/feature/I2CPositionEncoder.cpp @@ -358,7 +358,7 @@ bool I2CPositionEncoder::test_axis() { stepper.synchronize(); - planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS], + planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS], stepper.get_axis_position_mm(E_AXIS), feedrate, 0); stepper.synchronize(); @@ -415,10 +415,10 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { startCoord[encoderAxis] = startDistance; endCoord[encoderAxis] = endDistance; - LOOP_L_N(i, iter) { - stepper.synchronize(); + stepper.synchronize(); - planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS], + LOOP_L_N(i, iter) { + planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS], stepper.get_axis_position_mm(E_AXIS), feedrate, 0); stepper.synchronize(); @@ -427,7 +427,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { //do_blocking_move_to(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS]); - planner.buffer_line(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS], + planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS], stepper.get_axis_position_mm(E_AXIS), feedrate, 0); stepper.synchronize(); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 966636654..913316ecf 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -121,8 +121,8 @@ static void do_pause_e_move(const float &length, const float &fr) { set_destination_from_current(); destination[E_AXIS] += length / planner.e_factor[active_extruder]; planner.buffer_line_kinematic(destination, fr, active_extruder); - stepper.synchronize(); set_current_from_destination(); + stepper.synchronize(); } /** @@ -366,12 +366,12 @@ bool pause_print(const float &retract, const point_t &park_point, const float &u #endif print_job_timer.pause(); - // Wait for synchronize steppers - stepper.synchronize(); - // Save current position COPY(resume_position, current_position); + // Wait for buffered blocks to complete + stepper.synchronize(); + // Initial retract before move to filament change position if (retract && thermalManager.hotEnoughToExtrude(active_extruder)) do_pause_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 616cc58ee..9f3f4c03c 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -240,8 +240,6 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de destination[E_AXIS] = current_position[E_AXIS]; G26_line_to_destination(feed_value); - - stepper.synchronize(); set_destination_from_current(); } @@ -256,8 +254,6 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de destination[E_AXIS] += e_delta; G26_line_to_destination(feed_value); - - stepper.synchronize(); set_destination_from_current(); } @@ -499,13 +495,11 @@ inline bool prime_nozzle() { if (Total_Prime >= EXTRUDE_MAXLENGTH) return G26_ERR; #endif G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0); - + set_destination_from_current(); stepper.synchronize(); // Without this synchronize, the purge is more consistent, // but because the planner has a buffer, we won't be able // to stop as quickly. So we put up with the less smooth // action to give the user a more responsive 'Stop'. - set_destination_from_current(); - idle(); } wait_for_release(); @@ -526,7 +520,6 @@ inline bool prime_nozzle() { set_destination_from_current(); destination[E_AXIS] += g26_prime_length; G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0); - stepper.synchronize(); set_destination_from_current(); retract_filament(destination); } @@ -700,7 +693,6 @@ void GcodeSuite::G26() { if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) { do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - stepper.synchronize(); set_current_from_destination(); } diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 49b1fa7cb..8f33033af 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -949,8 +949,8 @@ void GcodeSuite::G29() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); #endif - enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT)); stepper.synchronize(); + enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT)); #endif // Auto Bed Leveling is complete! Enable if possible. diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index eb300b01d..eae35d1c4 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -108,7 +108,6 @@ void GcodeSuite::M81() { safe_delay(1000); // Wait 1 second before switching off #if HAS_SUICIDE - stepper.synchronize(); suicide(); #elif HAS_POWER_SWITCH PSU_OFF(); diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 5ca83eeda..af50da565 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -43,8 +43,6 @@ void report_current_position_detail() { - stepper.synchronize(); - SERIAL_PROTOCOLPGM("\nLogical:"); const float logical[XYZ] = { LOGICAL_X_POSITION(current_position[X_AXIS]), @@ -79,6 +77,8 @@ report_xyz(delta); #endif + stepper.synchronize(); + SERIAL_PROTOCOLPGM("Stepper:"); LOOP_XYZE(i) { SERIAL_CHAR(' '); diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index bd41673f3..453d02cd0 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -58,6 +58,8 @@ void GcodeSuite::M0_M1() { const bool has_message = !hasP && !hasS && args && *args; + stepper.synchronize(); + #if ENABLED(ULTIPANEL) if (has_message) @@ -81,8 +83,6 @@ void GcodeSuite::M0_M1() { KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; - stepper.synchronize(); - if (ms > 0) { ms += millis(); // wait until this time for a click while (PENDING(millis(), ms) && wait_for_user) idle(); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 66da41374..fdb92fb03 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -396,13 +396,13 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const f #endif - stepper.synchronize(); - feedrate_mm_s = old_feedrate_mm_s; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to"); #endif + + stepper.synchronize(); } void do_blocking_move_to_x(const float &rx, const float &fr_mm_s/*=0.0*/) { do_blocking_move_to(rx, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s); @@ -881,8 +881,8 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS }, current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate_mm_s[X_AXIS], 1 ); - SYNC_PLAN_POSITION_KINEMATIC(); stepper.synchronize(); + SYNC_PLAN_POSITION_KINEMATIC(); extruder_duplication_enabled = true; active_extruder_parked = false; #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -1106,7 +1106,7 @@ static void do_homing_move(const AxisEnum axis, const float distance, const floa planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate(axis), active_extruder); #else sync_plan_position(); - current_position[axis] = distance; + current_position[axis] = distance; // Set delta/cartesian axes directly planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate(axis), active_extruder); #endif