Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions Marlin/src/feature/I2CPositionEncoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand Down Expand Up @@ -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();

Expand All @@ -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();

Expand Down
45 changes: 21 additions & 24 deletions Marlin/src/feature/fwretract.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ void FWRetract::retract(const bool retracting
// G11 priority to recover the long retract if activated
if (!retracting) swapping = retracted_swap[active_extruder];
#else
const bool swapping = false;
constexpr bool swapping = false;
#endif

/* // debugging
Expand All @@ -118,62 +118,57 @@ void FWRetract::retract(const bool retracting
for (uint8_t i = 0; i < EXTRUDERS; ++i) {
SERIAL_ECHOPAIR("retracted[", i);
SERIAL_ECHOLNPAIR("] ", retracted[i]);
SERIAL_ECHOPAIR("retracted_swap[", i);
SERIAL_ECHOLNPAIR("] ", retracted_swap[i]);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR("retracted_swap[", i);
SERIAL_ECHOLNPAIR("] ", retracted_swap[i]);
#endif
}
SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]);
SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_AXIS]);
SERIAL_ECHOLNPAIR("hop_amount ", hop_amount);
//*/

const float old_feedrate_mm_s = feedrate_mm_s;
const float old_feedrate_mm_s = feedrate_mm_s,
renormalize = RECIPROCAL(planner.e_factor[active_extruder]),
base_retract = swapping ? swap_retract_length : retract_length,
old_z = current_position[Z_AXIS],
old_e = current_position[E_AXIS];

// The current position will be the destination for E and Z moves
set_destination_from_current();
stepper.synchronize(); // Wait for buffered moves to complete

const float renormalize = 1.0 / planner.e_factor[active_extruder];

if (retracting) {
// Retract by moving from a faux E position back to the current E position
feedrate_mm_s = retract_feedrate_mm_s;
current_position[E_AXIS] += (swapping ? swap_retract_length : retract_length) * renormalize;
sync_plan_position_e();
prepare_move_to_destination(); // set_current_to_destination
destination[E_AXIS] -= base_retract * renormalize;
prepare_move_to_destination(); // set_current_to_destination

// Is a Z hop set, and has the hop not yet been done?
// No double zlifting
// Feedrate to the max
if (retract_zlift > 0.01 && !hop_amount) { // Apply hop only once
const float old_z = current_position[Z_AXIS];
hop_amount += retract_zlift; // Add to the hop total (again, only once)
destination[Z_AXIS] += retract_zlift; // Raise Z by the zlift (M207 Z) amount
feedrate_mm_s = planner.max_feedrate_mm_s[Z_AXIS]; // Maximum Z feedrate
prepare_move_to_destination(); // Raise up, set_current_to_destination
current_position[Z_AXIS] = old_z; // Spoof the Z position in the planner
SYNC_PLAN_POSITION_KINEMATIC();
}
}
else {
// If a hop was done and Z hasn't changed, undo the Z hop
if (hop_amount) {
current_position[Z_AXIS] += hop_amount; // Set actual Z (due to the prior hop)
SYNC_PLAN_POSITION_KINEMATIC(); // Spoof the Z position in the planner
destination[Z_AXIS] -= hop_amount; // Move back down by the total hop amount
feedrate_mm_s = planner.max_feedrate_mm_s[Z_AXIS]; // Z feedrate to max
prepare_move_to_destination(); // Lower Z, set_current_to_destination
hop_amount = 0.0; // Clear the hop amount
}

// A retract multiplier has been added here to get faster swap recovery
destination[E_AXIS] += (base_retract + (swapping ? swap_retract_recover_length : retract_recover_length)) * renormalize;
feedrate_mm_s = swapping ? swap_retract_recover_feedrate_mm_s : retract_recover_feedrate_mm_s;

current_position[E_AXIS] -= (swapping ? swap_retract_length + swap_retract_recover_length
: retract_length + retract_recover_length) * renormalize;
sync_plan_position_e();
prepare_move_to_destination(); // Recover E, set_current_to_destination
}

feedrate_mm_s = old_feedrate_mm_s; // Restore original feedrate
current_position[Z_AXIS] = old_z; // Restore Z and E positions
current_position[E_AXIS] = old_e;
SYNC_PLAN_POSITION_KINEMATIC(); // As if the move never took place

retracted[active_extruder] = retracting; // Active extruder now retracted / recovered

Expand All @@ -189,8 +184,10 @@ void FWRetract::retract(const bool retracting
for (uint8_t i = 0; i < EXTRUDERS; ++i) {
SERIAL_ECHOPAIR("retracted[", i);
SERIAL_ECHOLNPAIR("] ", retracted[i]);
SERIAL_ECHOPAIR("retracted_swap[", i);
SERIAL_ECHOLNPAIR("] ", retracted_swap[i]);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR("retracted_swap[", i);
SERIAL_ECHOLNPAIR("] ", retracted_swap[i]);
#endif
}
SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]);
SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_AXIS]);
Expand Down
8 changes: 4 additions & 4 deletions Marlin/src/feature/pause.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

/**
Expand Down Expand Up @@ -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);
Expand Down
10 changes: 1 addition & 9 deletions Marlin/src/gcode/bedlevel/G26.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

Expand All @@ -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();
}

Expand Down Expand Up @@ -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();
Expand All @@ -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);
}
Expand Down Expand Up @@ -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();
}

Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/gcode/bedlevel/abl/G29.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
1 change: 0 additions & 1 deletion Marlin/src/gcode/control/M80_M81.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
8 changes: 2 additions & 6 deletions Marlin/src/gcode/geometry/G92.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,6 @@
*/
void GcodeSuite::G92() {

stepper.synchronize();

#if ENABLED(CNC_COORDINATE_SYSTEMS)
switch (parser.subcode) {
case 1:
Expand Down Expand Up @@ -94,10 +92,8 @@ void GcodeSuite::G92() {
COPY(coordinate_system[active_coordinate_system], position_shift);
#endif

if (didXYZ)
SYNC_PLAN_POSITION_KINEMATIC();
else if (didE)
sync_plan_position_e();
if (didXYZ) SYNC_PLAN_POSITION_KINEMATIC();
else if (didE) sync_plan_position_e();

report_current_position();
}
4 changes: 2 additions & 2 deletions Marlin/src/gcode/host/M114.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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]),
Expand Down Expand Up @@ -79,6 +77,8 @@
report_xyz(delta);
#endif

stepper.synchronize();

SERIAL_PROTOCOLPGM("Stepper:");
LOOP_XYZE(i) {
SERIAL_CHAR(' ');
Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/gcode/lcd/M0_M1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ void GcodeSuite::M0_M1() {

const bool has_message = !hasP && !hasS && args && *args;

stepper.synchronize();

#if ENABLED(ULTIPANEL)

if (has_message)
Expand All @@ -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();
Expand Down
8 changes: 4 additions & 4 deletions Marlin/src/module/motion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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

Expand Down
Loading