Browse Source

Adjust usage of stepper.synchronize

Scott Lahteine 7 years ago
parent
commit
bfe223e120

+ 5
- 5
Marlin/src/feature/I2CPositionEncoder.cpp View File

@@ -358,7 +358,7 @@ bool I2CPositionEncoder::test_axis() {
358 358
 
359 359
   stepper.synchronize();
360 360
 
361
-  planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS],
361
+  planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS],
362 362
                       stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
363 363
   stepper.synchronize();
364 364
 
@@ -415,10 +415,10 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
415 415
   startCoord[encoderAxis] = startDistance;
416 416
   endCoord[encoderAxis] = endDistance;
417 417
 
418
-  LOOP_L_N(i, iter) {
419
-    stepper.synchronize();
418
+  stepper.synchronize();
420 419
 
421
-    planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS],
420
+  LOOP_L_N(i, iter) {
421
+    planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS],
422 422
                         stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
423 423
     stepper.synchronize();
424 424
 
@@ -427,7 +427,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
427 427
 
428 428
     //do_blocking_move_to(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS]);
429 429
 
430
-    planner.buffer_line(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS],
430
+    planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS],
431 431
                         stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
432 432
     stepper.synchronize();
433 433
 

+ 4
- 4
Marlin/src/feature/pause.cpp View File

@@ -121,8 +121,8 @@ static void do_pause_e_move(const float &length, const float &fr) {
121 121
   set_destination_from_current();
122 122
   destination[E_AXIS] += length / planner.e_factor[active_extruder];
123 123
   planner.buffer_line_kinematic(destination, fr, active_extruder);
124
-  stepper.synchronize();
125 124
   set_current_from_destination();
125
+  stepper.synchronize();
126 126
 }
127 127
 
128 128
 /**
@@ -366,12 +366,12 @@ bool pause_print(const float &retract, const point_t &park_point, const float &u
366 366
   #endif
367 367
   print_job_timer.pause();
368 368
 
369
-  // Wait for synchronize steppers
370
-  stepper.synchronize();
371
-
372 369
   // Save current position
373 370
   COPY(resume_position, current_position);
374 371
 
372
+  // Wait for buffered blocks to complete
373
+  stepper.synchronize();
374
+
375 375
   // Initial retract before move to filament change position
376 376
   if (retract && thermalManager.hotEnoughToExtrude(active_extruder))
377 377
     do_pause_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE);

+ 1
- 9
Marlin/src/gcode/bedlevel/G26.cpp View File

@@ -240,8 +240,6 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de
240 240
     destination[E_AXIS] = current_position[E_AXIS];
241 241
 
242 242
     G26_line_to_destination(feed_value);
243
-
244
-    stepper.synchronize();
245 243
     set_destination_from_current();
246 244
   }
247 245
 
@@ -256,8 +254,6 @@ void move_to(const float &rx, const float &ry, const float &z, const float &e_de
256 254
   destination[E_AXIS] += e_delta;
257 255
 
258 256
   G26_line_to_destination(feed_value);
259
-
260
-  stepper.synchronize();
261 257
   set_destination_from_current();
262 258
 }
263 259
 
@@ -499,13 +495,11 @@ inline bool prime_nozzle() {
499 495
           if (Total_Prime >= EXTRUDE_MAXLENGTH) return G26_ERR;
500 496
         #endif
501 497
         G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
502
-
498
+        set_destination_from_current();
503 499
         stepper.synchronize();    // Without this synchronize, the purge is more consistent,
504 500
                                   // but because the planner has a buffer, we won't be able
505 501
                                   // to stop as quickly. So we put up with the less smooth
506 502
                                   // action to give the user a more responsive 'Stop'.
507
-        set_destination_from_current();
508
-        idle();
509 503
       }
510 504
 
511 505
       wait_for_release();
@@ -526,7 +520,6 @@ inline bool prime_nozzle() {
526 520
     set_destination_from_current();
527 521
     destination[E_AXIS] += g26_prime_length;
528 522
     G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
529
-    stepper.synchronize();
530 523
     set_destination_from_current();
531 524
     retract_filament(destination);
532 525
   }
@@ -700,7 +693,6 @@ void GcodeSuite::G26() {
700 693
 
701 694
   if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) {
702 695
     do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
703
-    stepper.synchronize();
704 696
     set_current_from_destination();
705 697
   }
706 698
 

+ 1
- 1
Marlin/src/gcode/bedlevel/abl/G29.cpp View File

@@ -949,8 +949,8 @@ void GcodeSuite::G29() {
949 949
       #if ENABLED(DEBUG_LEVELING_FEATURE)
950 950
         if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT);
951 951
       #endif
952
-      enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT));
953 952
       stepper.synchronize();
953
+      enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT));
954 954
     #endif
955 955
 
956 956
     // Auto Bed Leveling is complete! Enable if possible.

+ 0
- 1
Marlin/src/gcode/control/M80_M81.cpp View File

@@ -108,7 +108,6 @@ void GcodeSuite::M81() {
108 108
   safe_delay(1000); // Wait 1 second before switching off
109 109
 
110 110
   #if HAS_SUICIDE
111
-    stepper.synchronize();
112 111
     suicide();
113 112
   #elif HAS_POWER_SWITCH
114 113
     PSU_OFF();

+ 2
- 2
Marlin/src/gcode/host/M114.cpp View File

@@ -43,8 +43,6 @@
43 43
 
44 44
   void report_current_position_detail() {
45 45
 
46
-    stepper.synchronize();
47
-
48 46
     SERIAL_PROTOCOLPGM("\nLogical:");
49 47
     const float logical[XYZ] = {
50 48
       LOGICAL_X_POSITION(current_position[X_AXIS]),
@@ -79,6 +77,8 @@
79 77
       report_xyz(delta);
80 78
     #endif
81 79
 
80
+    stepper.synchronize();
81
+
82 82
     SERIAL_PROTOCOLPGM("Stepper:");
83 83
     LOOP_XYZE(i) {
84 84
       SERIAL_CHAR(' ');

+ 2
- 2
Marlin/src/gcode/lcd/M0_M1.cpp View File

@@ -58,6 +58,8 @@ void GcodeSuite::M0_M1() {
58 58
 
59 59
   const bool has_message = !hasP && !hasS && args && *args;
60 60
 
61
+  stepper.synchronize();
62
+
61 63
   #if ENABLED(ULTIPANEL)
62 64
 
63 65
     if (has_message)
@@ -81,8 +83,6 @@ void GcodeSuite::M0_M1() {
81 83
   KEEPALIVE_STATE(PAUSED_FOR_USER);
82 84
   wait_for_user = true;
83 85
 
84
-  stepper.synchronize();
85
-
86 86
   if (ms > 0) {
87 87
     ms += millis();  // wait until this time for a click
88 88
     while (PENDING(millis(), ms) && wait_for_user) idle();

+ 4
- 4
Marlin/src/module/motion.cpp View File

@@ -396,13 +396,13 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const f
396 396
 
397 397
   #endif
398 398
 
399
-  stepper.synchronize();
400
-
401 399
   feedrate_mm_s = old_feedrate_mm_s;
402 400
 
403 401
   #if ENABLED(DEBUG_LEVELING_FEATURE)
404 402
     if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to");
405 403
   #endif
404
+
405
+  stepper.synchronize();
406 406
 }
407 407
 void do_blocking_move_to_x(const float &rx, const float &fr_mm_s/*=0.0*/) {
408 408
   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 },
881 881
               current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS],
882 882
               planner.max_feedrate_mm_s[X_AXIS], 1
883 883
             );
884
-            SYNC_PLAN_POSITION_KINEMATIC();
885 884
             stepper.synchronize();
885
+            SYNC_PLAN_POSITION_KINEMATIC();
886 886
             extruder_duplication_enabled = true;
887 887
             active_extruder_parked = false;
888 888
             #if ENABLED(DEBUG_LEVELING_FEATURE)
@@ -1106,7 +1106,7 @@ static void do_homing_move(const AxisEnum axis, const float distance, const floa
1106 1106
     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);
1107 1107
   #else
1108 1108
     sync_plan_position();
1109
-    current_position[axis] = distance;
1109
+    current_position[axis] = distance; // Set delta/cartesian axes directly
1110 1110
     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);
1111 1111
   #endif
1112 1112
 

Loading…
Cancel
Save