Browse Source

Consolidate "bedlevel" code

Scott Lahteine 7 years ago
parent
commit
551752eac7
45 changed files with 3618 additions and 3944 deletions
  1. 135
    2508
      Marlin/src/Marlin.cpp
  2. 8
    79
      Marlin/src/Marlin.h
  3. 425
    0
      Marlin/src/feature/bedlevel/abl/abl.cpp
  4. 51
    0
      Marlin/src/feature/bedlevel/abl/abl.h
  5. 314
    0
      Marlin/src/feature/bedlevel/bedlevel.cpp
  6. 72
    0
      Marlin/src/feature/bedlevel/bedlevel.h
  7. 12
    2
      Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp
  8. 5
    1
      Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h
  9. 9
    5
      Marlin/src/feature/bedlevel/ubl/ubl.cpp
  10. 40
    16
      Marlin/src/feature/bedlevel/ubl/ubl.h
  11. 18
    18
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  12. 9
    24
      Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
  13. 0
    893
      Marlin/src/feature/ubl/G26_Mesh_Validation_Tool.cpp
  14. 17
    3
      Marlin/src/gcode/bedlevel/M420.cpp
  15. 33
    8
      Marlin/src/gcode/bedlevel/abl/G29.cpp
  16. 14
    1
      Marlin/src/gcode/bedlevel/abl/M421.cpp
  17. 20
    14
      Marlin/src/gcode/bedlevel/mbl/G29.cpp
  18. 15
    1
      Marlin/src/gcode/bedlevel/mbl/M421.cpp
  19. 12
    3
      Marlin/src/gcode/bedlevel/ubl/G26.cpp
  20. 12
    3
      Marlin/src/gcode/bedlevel/ubl/G29.cpp
  21. 14
    1
      Marlin/src/gcode/bedlevel/ubl/M421.cpp
  22. 14
    1
      Marlin/src/gcode/bedlevel/ubl/M49.cpp
  23. 17
    6
      Marlin/src/gcode/calibrate/G28.cpp
  24. 0
    65
      Marlin/src/gcode/calibrate/G29.h
  25. 41
    22
      Marlin/src/gcode/calibrate/G33.cpp
  26. 5
    5
      Marlin/src/gcode/calibrate/M666.h
  27. 0
    81
      Marlin/src/gcode/calibrate/common.h
  28. 1
    1
      Marlin/src/gcode/control/M18_M84.h
  29. 16
    32
      Marlin/src/gcode/gcode.cpp
  30. 8
    34
      Marlin/src/gcode/probe/M851.cpp
  31. 6
    5
      Marlin/src/lcd/ultralcd.cpp
  32. 1
    1
      Marlin/src/lcd/ultralcd_impl_DOGM.h
  33. 1
    1
      Marlin/src/lcd/ultralcd_impl_HD44780.h
  34. 11
    15
      Marlin/src/module/configuration_store.cpp
  35. 269
    0
      Marlin/src/module/delta.cpp
  36. 141
    0
      Marlin/src/module/delta.h
  37. 770
    73
      Marlin/src/module/motion.cpp
  38. 87
    11
      Marlin/src/module/motion.h
  39. 8
    10
      Marlin/src/module/planner.cpp
  40. 7
    1
      Marlin/src/module/planner.h
  41. 709
    0
      Marlin/src/module/probe.cpp
  42. 69
    0
      Marlin/src/module/probe.h
  43. 155
    0
      Marlin/src/module/scara.cpp
  44. 46
    0
      Marlin/src/module/scara.h
  45. 1
    0
      Marlin/src/module/stepper.cpp

+ 135
- 2508
Marlin/src/Marlin.cpp
File diff suppressed because it is too large
View File


+ 8
- 79
Marlin/src/Marlin.h View File

@@ -48,10 +48,6 @@ void idle(
48 48
 
49 49
 void manage_inactivity(bool ignore_stepper_queue = false);
50 50
 
51
-#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
52
-  extern bool extruder_duplication_enabled;
53
-#endif
54
-
55 51
 #if HAS_X2_ENABLE
56 52
   #define  enable_X() do{ X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); }while(0)
57 53
   #define disable_X() do{ X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }while(0)
@@ -179,13 +175,6 @@ extern bool Running;
179 175
 inline bool IsRunning() { return  Running; }
180 176
 inline bool IsStopped() { return !Running; }
181 177
 
182
-/**
183
- * Feedrate scaling and conversion
184
- */
185
-extern int16_t feedrate_percentage;
186
-
187
-#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
188
-
189 178
 extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
190 179
 extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
191 180
 
@@ -197,71 +186,23 @@ extern volatile bool wait_for_heatup;
197 186
   extern volatile bool wait_for_user;
198 187
 #endif
199 188
 
200
-// Hotend Offsets
201
-#if HOTENDS > 1
202
-  extern float hotend_offset[XYZ][HOTENDS];
203
-#endif
204
-
205
-// Software Endstops
206
-extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
207
-
208
-#if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE)
209
-  void update_software_endstops(const AxisEnum axis);
210
-#endif
211
-
212
-#if IS_KINEMATIC
213
-  extern float delta[ABC];
214
-  void inverse_kinematics(const float logical[XYZ]);
215
-#endif
216
-
217
-#if ENABLED(DELTA)
218
-  extern float endstop_adj[ABC],
219
-               delta_radius,
220
-               delta_diagonal_rod,
221
-               delta_calibration_radius,
222
-               delta_segments_per_second,
223
-               delta_tower_angle_trim[2],
224
-               delta_clip_start_height;
225
-  void recalc_delta_settings(float radius, float diagonal_rod);
226
-#elif IS_SCARA
227
-  void forward_kinematics_SCARA(const float &a, const float &b);
228
-#endif
229
-
230
-#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
231
-  extern int bilinear_grid_spacing[2], bilinear_start[2];
232
-  extern float bilinear_grid_factor[2],
233
-               z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
234
-  float bilinear_z_offset(const float logical[XYZ]);
235
-#endif
236
-
237 189
 #if ENABLED(AUTO_BED_LEVELING_UBL)
238 190
   typedef struct { double A, B, D; } linear_fit;
239 191
   linear_fit* lsf_linear_fit(double x[], double y[], double z[], const int);
240 192
 #endif
241 193
 
242
-#if HAS_LEVELING
243
-  bool leveling_is_valid();
244
-  bool leveling_is_active();
245
-  void set_bed_leveling_enabled(const bool enable=true);
246
-  void reset_bed_level();
247
-#endif
248
-
249
-#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
250
-  void set_z_fade_height(const float zfh);
251
-#endif
252
-
253 194
 #if ENABLED(Z_DUAL_ENDSTOPS)
254 195
   extern float z_endstop_adj;
255 196
 #endif
256 197
 
257
-#if HAS_BED_PROBE
258
-  extern float zprobe_zoffset;
259
-  void refresh_zprobe_zoffset(const bool no_babystep=false);
260
-  #define DEPLOY_PROBE() set_probe_deployed(true)
261
-  #define STOW_PROBE() set_probe_deployed(false)
262
-#else
263
-  #define DEPLOY_PROBE()
264
-  #define STOW_PROBE()
198
+#if HAS_SERVOS
199
+  #include "HAL/servo.h"
200
+  extern HAL_SERVO_LIB servo[NUM_SERVOS];
201
+  #define MOVE_SERVO(I, P) servo[I].move(P)
202
+  #if HAS_Z_SERVO_ENDSTOP
203
+    #define DEPLOY_Z_SERVO() MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[0])
204
+    #define STOW_Z_SERVO() MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[1])
205
+  #endif
265 206
 #endif
266 207
 
267 208
 #if FAN_COUNT > 0
@@ -309,16 +250,4 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
309 250
 
310 251
 void calculate_volumetric_multipliers();
311 252
 
312
-/**
313
- * Blocking movement and shorthand functions
314
- */
315
-void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s=0.0);
316
-void do_blocking_move_to_x(const float &x, const float &fr_mm_s=0.0);
317
-void do_blocking_move_to_z(const float &z, const float &fr_mm_s=0.0);
318
-void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s=0.0);
319
-
320
-#if ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE)
321
-  bool axis_unhomed_error(const bool x=true, const bool y=true, const bool z=true);
322
-#endif
323
-
324 253
 #endif // __MARLIN_H__

+ 425
- 0
Marlin/src/feature/bedlevel/abl/abl.cpp View File

@@ -0,0 +1,425 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#include "../../../inc/MarlinConfig.h"
24
+
25
+#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
26
+
27
+#include "abl.h"
28
+
29
+#include "../../../module/motion.h"
30
+
31
+int bilinear_grid_spacing[2], bilinear_start[2];
32
+float bilinear_grid_factor[2],
33
+      z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
34
+
35
+/**
36
+ * Extrapolate a single point from its neighbors
37
+ */
38
+static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) {
39
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
40
+    if (DEBUGGING(LEVELING)) {
41
+      SERIAL_ECHOPGM("Extrapolate [");
42
+      if (x < 10) SERIAL_CHAR(' ');
43
+      SERIAL_ECHO((int)x);
44
+      SERIAL_CHAR(xdir ? (xdir > 0 ? '+' : '-') : ' ');
45
+      SERIAL_CHAR(' ');
46
+      if (y < 10) SERIAL_CHAR(' ');
47
+      SERIAL_ECHO((int)y);
48
+      SERIAL_CHAR(ydir ? (ydir > 0 ? '+' : '-') : ' ');
49
+      SERIAL_CHAR(']');
50
+    }
51
+  #endif
52
+  if (!isnan(z_values[x][y])) {
53
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
54
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM(" (done)");
55
+    #endif
56
+    return;  // Don't overwrite good values.
57
+  }
58
+  SERIAL_EOL();
59
+
60
+  // Get X neighbors, Y neighbors, and XY neighbors
61
+  const uint8_t x1 = x + xdir, y1 = y + ydir, x2 = x1 + xdir, y2 = y1 + ydir;
62
+  float a1 = z_values[x1][y ], a2 = z_values[x2][y ],
63
+        b1 = z_values[x ][y1], b2 = z_values[x ][y2],
64
+        c1 = z_values[x1][y1], c2 = z_values[x2][y2];
65
+
66
+  // Treat far unprobed points as zero, near as equal to far
67
+  if (isnan(a2)) a2 = 0.0; if (isnan(a1)) a1 = a2;
68
+  if (isnan(b2)) b2 = 0.0; if (isnan(b1)) b1 = b2;
69
+  if (isnan(c2)) c2 = 0.0; if (isnan(c1)) c1 = c2;
70
+
71
+  const float a = 2 * a1 - a2, b = 2 * b1 - b2, c = 2 * c1 - c2;
72
+
73
+  // Take the average instead of the median
74
+  z_values[x][y] = (a + b + c) / 3.0;
75
+
76
+  // Median is robust (ignores outliers).
77
+  // z_values[x][y] = (a < b) ? ((b < c) ? b : (c < a) ? a : c)
78
+  //                                : ((c < b) ? b : (a < c) ? a : c);
79
+}
80
+
81
+//Enable this if your SCARA uses 180° of total area
82
+//#define EXTRAPOLATE_FROM_EDGE
83
+
84
+#if ENABLED(EXTRAPOLATE_FROM_EDGE)
85
+  #if GRID_MAX_POINTS_X < GRID_MAX_POINTS_Y
86
+    #define HALF_IN_X
87
+  #elif GRID_MAX_POINTS_Y < GRID_MAX_POINTS_X
88
+    #define HALF_IN_Y
89
+  #endif
90
+#endif
91
+
92
+/**
93
+ * Fill in the unprobed points (corners of circular print surface)
94
+ * using linear extrapolation, away from the center.
95
+ */
96
+void extrapolate_unprobed_bed_level() {
97
+  #ifdef HALF_IN_X
98
+    constexpr uint8_t ctrx2 = 0, xlen = GRID_MAX_POINTS_X - 1;
99
+  #else
100
+    constexpr uint8_t ctrx1 = (GRID_MAX_POINTS_X - 1) / 2, // left-of-center
101
+                      ctrx2 = (GRID_MAX_POINTS_X) / 2,     // right-of-center
102
+                      xlen = ctrx1;
103
+  #endif
104
+
105
+  #ifdef HALF_IN_Y
106
+    constexpr uint8_t ctry2 = 0, ylen = GRID_MAX_POINTS_Y - 1;
107
+  #else
108
+    constexpr uint8_t ctry1 = (GRID_MAX_POINTS_Y - 1) / 2, // top-of-center
109
+                      ctry2 = (GRID_MAX_POINTS_Y) / 2,     // bottom-of-center
110
+                      ylen = ctry1;
111
+  #endif
112
+
113
+  for (uint8_t xo = 0; xo <= xlen; xo++)
114
+    for (uint8_t yo = 0; yo <= ylen; yo++) {
115
+      uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo;
116
+      #ifndef HALF_IN_X
117
+        const uint8_t x1 = ctrx1 - xo;
118
+      #endif
119
+      #ifndef HALF_IN_Y
120
+        const uint8_t y1 = ctry1 - yo;
121
+        #ifndef HALF_IN_X
122
+          extrapolate_one_point(x1, y1, +1, +1);   //  left-below + +
123
+        #endif
124
+        extrapolate_one_point(x2, y1, -1, +1);     // right-below - +
125
+      #endif
126
+      #ifndef HALF_IN_X
127
+        extrapolate_one_point(x1, y2, +1, -1);     //  left-above + -
128
+      #endif
129
+      extrapolate_one_point(x2, y2, -1, -1);       // right-above - -
130
+    }
131
+
132
+}
133
+
134
+void print_bilinear_leveling_grid() {
135
+  SERIAL_ECHOLNPGM("Bilinear Leveling Grid:");
136
+  print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 3,
137
+    [](const uint8_t ix, const uint8_t iy) { return z_values[ix][iy]; }
138
+  );
139
+}
140
+
141
+#if ENABLED(ABL_BILINEAR_SUBDIVISION)
142
+
143
+  #define ABL_GRID_POINTS_VIRT_X (GRID_MAX_POINTS_X - 1) * (BILINEAR_SUBDIVISIONS) + 1
144
+  #define ABL_GRID_POINTS_VIRT_Y (GRID_MAX_POINTS_Y - 1) * (BILINEAR_SUBDIVISIONS) + 1
145
+  #define ABL_TEMP_POINTS_X (GRID_MAX_POINTS_X + 2)
146
+  #define ABL_TEMP_POINTS_Y (GRID_MAX_POINTS_Y + 2)
147
+  float z_values_virt[ABL_GRID_POINTS_VIRT_X][ABL_GRID_POINTS_VIRT_Y];
148
+  int bilinear_grid_spacing_virt[2] = { 0 };
149
+  float bilinear_grid_factor_virt[2] = { 0 };
150
+
151
+  void print_bilinear_leveling_grid_virt() {
152
+    SERIAL_ECHOLNPGM("Subdivided with CATMULL ROM Leveling Grid:");
153
+    print_2d_array(ABL_GRID_POINTS_VIRT_X, ABL_GRID_POINTS_VIRT_Y, 5,
154
+      [](const uint8_t ix, const uint8_t iy) { return z_values_virt[ix][iy]; }
155
+    );
156
+  }
157
+
158
+  #define LINEAR_EXTRAPOLATION(E, I) ((E) * 2 - (I))
159
+  float bed_level_virt_coord(const uint8_t x, const uint8_t y) {
160
+    uint8_t ep = 0, ip = 1;
161
+    if (!x || x == ABL_TEMP_POINTS_X - 1) {
162
+      if (x) {
163
+        ep = GRID_MAX_POINTS_X - 1;
164
+        ip = GRID_MAX_POINTS_X - 2;
165
+      }
166
+      if (WITHIN(y, 1, ABL_TEMP_POINTS_Y - 2))
167
+        return LINEAR_EXTRAPOLATION(
168
+          z_values[ep][y - 1],
169
+          z_values[ip][y - 1]
170
+        );
171
+      else
172
+        return LINEAR_EXTRAPOLATION(
173
+          bed_level_virt_coord(ep + 1, y),
174
+          bed_level_virt_coord(ip + 1, y)
175
+        );
176
+    }
177
+    if (!y || y == ABL_TEMP_POINTS_Y - 1) {
178
+      if (y) {
179
+        ep = GRID_MAX_POINTS_Y - 1;
180
+        ip = GRID_MAX_POINTS_Y - 2;
181
+      }
182
+      if (WITHIN(x, 1, ABL_TEMP_POINTS_X - 2))
183
+        return LINEAR_EXTRAPOLATION(
184
+          z_values[x - 1][ep],
185
+          z_values[x - 1][ip]
186
+        );
187
+      else
188
+        return LINEAR_EXTRAPOLATION(
189
+          bed_level_virt_coord(x, ep + 1),
190
+          bed_level_virt_coord(x, ip + 1)
191
+        );
192
+    }
193
+    return z_values[x - 1][y - 1];
194
+  }
195
+
196
+  static float bed_level_virt_cmr(const float p[4], const uint8_t i, const float t) {
197
+    return (
198
+        p[i-1] * -t * sq(1 - t)
199
+      + p[i]   * (2 - 5 * sq(t) + 3 * t * sq(t))
200
+      + p[i+1] * t * (1 + 4 * t - 3 * sq(t))
201
+      - p[i+2] * sq(t) * (1 - t)
202
+    ) * 0.5;
203
+  }
204
+
205
+  static float bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const float &tx, const float &ty) {
206
+    float row[4], column[4];
207
+    for (uint8_t i = 0; i < 4; i++) {
208
+      for (uint8_t j = 0; j < 4; j++) {
209
+        column[j] = bed_level_virt_coord(i + x - 1, j + y - 1);
210
+      }
211
+      row[i] = bed_level_virt_cmr(column, 1, ty);
212
+    }
213
+    return bed_level_virt_cmr(row, 1, tx);
214
+  }
215
+
216
+  void bed_level_virt_interpolate() {
217
+    bilinear_grid_spacing_virt[X_AXIS] = bilinear_grid_spacing[X_AXIS] / (BILINEAR_SUBDIVISIONS);
218
+    bilinear_grid_spacing_virt[Y_AXIS] = bilinear_grid_spacing[Y_AXIS] / (BILINEAR_SUBDIVISIONS);
219
+    bilinear_grid_factor_virt[X_AXIS] = RECIPROCAL(bilinear_grid_spacing_virt[X_AXIS]);
220
+    bilinear_grid_factor_virt[Y_AXIS] = RECIPROCAL(bilinear_grid_spacing_virt[Y_AXIS]);
221
+    for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
222
+      for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
223
+        for (uint8_t ty = 0; ty < BILINEAR_SUBDIVISIONS; ty++)
224
+          for (uint8_t tx = 0; tx < BILINEAR_SUBDIVISIONS; tx++) {
225
+            if ((ty && y == GRID_MAX_POINTS_Y - 1) || (tx && x == GRID_MAX_POINTS_X - 1))
226
+              continue;
227
+            z_values_virt[x * (BILINEAR_SUBDIVISIONS) + tx][y * (BILINEAR_SUBDIVISIONS) + ty] =
228
+              bed_level_virt_2cmr(
229
+                x + 1,
230
+                y + 1,
231
+                (float)tx / (BILINEAR_SUBDIVISIONS),
232
+                (float)ty / (BILINEAR_SUBDIVISIONS)
233
+              );
234
+          }
235
+  }
236
+#endif // ABL_BILINEAR_SUBDIVISION
237
+
238
+// Refresh after other values have been updated
239
+void refresh_bed_level() {
240
+  bilinear_grid_factor[X_AXIS] = RECIPROCAL(bilinear_grid_spacing[X_AXIS]);
241
+  bilinear_grid_factor[Y_AXIS] = RECIPROCAL(bilinear_grid_spacing[Y_AXIS]);
242
+  #if ENABLED(ABL_BILINEAR_SUBDIVISION)
243
+    bed_level_virt_interpolate();
244
+  #endif
245
+}
246
+
247
+#if ENABLED(ABL_BILINEAR_SUBDIVISION)
248
+  #define ABL_BG_SPACING(A) bilinear_grid_spacing_virt[A]
249
+  #define ABL_BG_FACTOR(A)  bilinear_grid_factor_virt[A]
250
+  #define ABL_BG_POINTS_X   ABL_GRID_POINTS_VIRT_X
251
+  #define ABL_BG_POINTS_Y   ABL_GRID_POINTS_VIRT_Y
252
+  #define ABL_BG_GRID(X,Y)  z_values_virt[X][Y]
253
+#else
254
+  #define ABL_BG_SPACING(A) bilinear_grid_spacing[A]
255
+  #define ABL_BG_FACTOR(A)  bilinear_grid_factor[A]
256
+  #define ABL_BG_POINTS_X   GRID_MAX_POINTS_X
257
+  #define ABL_BG_POINTS_Y   GRID_MAX_POINTS_Y
258
+  #define ABL_BG_GRID(X,Y)  z_values[X][Y]
259
+#endif
260
+
261
+// Get the Z adjustment for non-linear bed leveling
262
+float bilinear_z_offset(const float logical[XYZ]) {
263
+
264
+  static float z1, d2, z3, d4, L, D, ratio_x, ratio_y,
265
+               last_x = -999.999, last_y = -999.999;
266
+
267
+  // Whole units for the grid line indices. Constrained within bounds.
268
+  static int8_t gridx, gridy, nextx, nexty,
269
+                last_gridx = -99, last_gridy = -99;
270
+
271
+  // XY relative to the probed area
272
+  const float x = RAW_X_POSITION(logical[X_AXIS]) - bilinear_start[X_AXIS],
273
+              y = RAW_Y_POSITION(logical[Y_AXIS]) - bilinear_start[Y_AXIS];
274
+
275
+  #if ENABLED(EXTRAPOLATE_BEYOND_GRID)
276
+    // Keep using the last grid box
277
+    #define FAR_EDGE_OR_BOX 2
278
+  #else
279
+    // Just use the grid far edge
280
+    #define FAR_EDGE_OR_BOX 1
281
+  #endif
282
+
283
+  if (last_x != x) {
284
+    last_x = x;
285
+    ratio_x = x * ABL_BG_FACTOR(X_AXIS);
286
+    const float gx = constrain(FLOOR(ratio_x), 0, ABL_BG_POINTS_X - FAR_EDGE_OR_BOX);
287
+    ratio_x -= gx;      // Subtract whole to get the ratio within the grid box
288
+
289
+    #if DISABLED(EXTRAPOLATE_BEYOND_GRID)
290
+      // Beyond the grid maintain height at grid edges
291
+      NOLESS(ratio_x, 0); // Never < 0.0. (> 1.0 is ok when nextx==gridx.)
292
+    #endif
293
+
294
+    gridx = gx;
295
+    nextx = min(gridx + 1, ABL_BG_POINTS_X - 1);
296
+  }
297
+
298
+  if (last_y != y || last_gridx != gridx) {
299
+
300
+    if (last_y != y) {
301
+      last_y = y;
302
+      ratio_y = y * ABL_BG_FACTOR(Y_AXIS);
303
+      const float gy = constrain(FLOOR(ratio_y), 0, ABL_BG_POINTS_Y - FAR_EDGE_OR_BOX);
304
+      ratio_y -= gy;
305
+
306
+      #if DISABLED(EXTRAPOLATE_BEYOND_GRID)
307
+        // Beyond the grid maintain height at grid edges
308
+        NOLESS(ratio_y, 0); // Never < 0.0. (> 1.0 is ok when nexty==gridy.)
309
+      #endif
310
+
311
+      gridy = gy;
312
+      nexty = min(gridy + 1, ABL_BG_POINTS_Y - 1);
313
+    }
314
+
315
+    if (last_gridx != gridx || last_gridy != gridy) {
316
+      last_gridx = gridx;
317
+      last_gridy = gridy;
318
+      // Z at the box corners
319
+      z1 = ABL_BG_GRID(gridx, gridy);       // left-front
320
+      d2 = ABL_BG_GRID(gridx, nexty) - z1;  // left-back (delta)
321
+      z3 = ABL_BG_GRID(nextx, gridy);       // right-front
322
+      d4 = ABL_BG_GRID(nextx, nexty) - z3;  // right-back (delta)
323
+    }
324
+
325
+    // Bilinear interpolate. Needed since y or gridx has changed.
326
+                L = z1 + d2 * ratio_y;   // Linear interp. LF -> LB
327
+    const float R = z3 + d4 * ratio_y;   // Linear interp. RF -> RB
328
+
329
+    D = R - L;
330
+  }
331
+
332
+  const float offset = L + ratio_x * D;   // the offset almost always changes
333
+
334
+  /*
335
+  static float last_offset = 0;
336
+  if (FABS(last_offset - offset) > 0.2) {
337
+    SERIAL_ECHOPGM("Sudden Shift at ");
338
+    SERIAL_ECHOPAIR("x=", x);
339
+    SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]);
340
+    SERIAL_ECHOLNPAIR(" -> gridx=", gridx);
341
+    SERIAL_ECHOPAIR(" y=", y);
342
+    SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[Y_AXIS]);
343
+    SERIAL_ECHOLNPAIR(" -> gridy=", gridy);
344
+    SERIAL_ECHOPAIR(" ratio_x=", ratio_x);
345
+    SERIAL_ECHOLNPAIR(" ratio_y=", ratio_y);
346
+    SERIAL_ECHOPAIR(" z1=", z1);
347
+    SERIAL_ECHOPAIR(" z2=", z2);
348
+    SERIAL_ECHOPAIR(" z3=", z3);
349
+    SERIAL_ECHOLNPAIR(" z4=", z4);
350
+    SERIAL_ECHOPAIR(" L=", L);
351
+    SERIAL_ECHOPAIR(" R=", R);
352
+    SERIAL_ECHOLNPAIR(" offset=", offset);
353
+  }
354
+  last_offset = offset;
355
+  //*/
356
+
357
+  return offset;
358
+}
359
+
360
+#if !IS_KINEMATIC
361
+
362
+  #define CELL_INDEX(A,V) ((RAW_##A##_POSITION(V) - bilinear_start[A##_AXIS]) * ABL_BG_FACTOR(A##_AXIS))
363
+
364
+  /**
365
+   * Prepare a bilinear-leveled linear move on Cartesian,
366
+   * splitting the move where it crosses grid borders.
367
+   */
368
+  void bilinear_line_to_destination(const float fr_mm_s, uint16_t x_splits, uint16_t y_splits) {
369
+    int cx1 = CELL_INDEX(X, current_position[X_AXIS]),
370
+        cy1 = CELL_INDEX(Y, current_position[Y_AXIS]),
371
+        cx2 = CELL_INDEX(X, destination[X_AXIS]),
372
+        cy2 = CELL_INDEX(Y, destination[Y_AXIS]);
373
+    cx1 = constrain(cx1, 0, ABL_BG_POINTS_X - 2);
374
+    cy1 = constrain(cy1, 0, ABL_BG_POINTS_Y - 2);
375
+    cx2 = constrain(cx2, 0, ABL_BG_POINTS_X - 2);
376
+    cy2 = constrain(cy2, 0, ABL_BG_POINTS_Y - 2);
377
+
378
+    if (cx1 == cx2 && cy1 == cy2) {
379
+      // Start and end on same mesh square
380
+      line_to_destination(fr_mm_s);
381
+      set_current_to_destination();
382
+      return;
383
+    }
384
+
385
+    #define LINE_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist)
386
+
387
+    float normalized_dist, end[XYZE];
388
+
389
+    // Split at the left/front border of the right/top square
390
+    const int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2);
391
+    if (cx2 != cx1 && TEST(x_splits, gcx)) {
392
+      COPY(end, destination);
393
+      destination[X_AXIS] = LOGICAL_X_POSITION(bilinear_start[X_AXIS] + ABL_BG_SPACING(X_AXIS) * gcx);
394
+      normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]);
395
+      destination[Y_AXIS] = LINE_SEGMENT_END(Y);
396
+      CBI(x_splits, gcx);
397
+    }
398
+    else if (cy2 != cy1 && TEST(y_splits, gcy)) {
399
+      COPY(end, destination);
400
+      destination[Y_AXIS] = LOGICAL_Y_POSITION(bilinear_start[Y_AXIS] + ABL_BG_SPACING(Y_AXIS) * gcy);
401
+      normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]);
402
+      destination[X_AXIS] = LINE_SEGMENT_END(X);
403
+      CBI(y_splits, gcy);
404
+    }
405
+    else {
406
+      // Already split on a border
407
+      line_to_destination(fr_mm_s);
408
+      set_current_to_destination();
409
+      return;
410
+    }
411
+
412
+    destination[Z_AXIS] = LINE_SEGMENT_END(Z);
413
+    destination[E_AXIS] = LINE_SEGMENT_END(E);
414
+
415
+    // Do the split and look for more borders
416
+    bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
417
+
418
+    // Restore destination from stack
419
+    COPY(destination, end);
420
+    bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
421
+  }
422
+
423
+#endif // !IS_KINEMATIC
424
+
425
+#endif // AUTO_BED_LEVELING_BILINEAR

+ 51
- 0
Marlin/src/feature/bedlevel/abl/abl.h View File

@@ -0,0 +1,51 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016, 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#ifndef __ABL_H__
24
+#define __ABL_H__
25
+
26
+#include "../../../inc/MarlinConfig.h"
27
+
28
+#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
29
+
30
+  #include "../bedlevel.h"
31
+
32
+  extern int bilinear_grid_spacing[2], bilinear_start[2];
33
+  extern float bilinear_grid_factor[2],
34
+               z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
35
+  float bilinear_z_offset(const float logical[XYZ]);
36
+
37
+  void extrapolate_unprobed_bed_level();
38
+  void print_bilinear_leveling_grid();
39
+  void refresh_bed_level();
40
+  #if ENABLED(ABL_BILINEAR_SUBDIVISION)
41
+    void print_bilinear_leveling_grid_virt();
42
+    void bed_level_virt_interpolate();
43
+  #endif
44
+
45
+  #if !IS_KINEMATIC
46
+    void bilinear_line_to_destination(const float fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF);
47
+  #endif
48
+
49
+#endif // AUTO_BED_LEVELING_BILINEAR
50
+
51
+#endif // __ABL_H__

+ 314
- 0
Marlin/src/feature/bedlevel/bedlevel.cpp View File

@@ -0,0 +1,314 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#include "../../inc/MarlinConfig.h"
24
+
25
+#if HAS_LEVELING
26
+
27
+#include "bedlevel.h"
28
+
29
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
30
+  #include "../../module/stepper.h"
31
+#endif
32
+
33
+#if PLANNER_LEVELING
34
+  #include "../../module/planner.h"
35
+#endif
36
+
37
+#if ENABLED(PROBE_MANUALLY)
38
+  bool g29_in_progress = false;
39
+  #if ENABLED(LCD_BED_LEVELING)
40
+    #include "../../lcd/ultralcd.h"
41
+  #endif
42
+#endif
43
+
44
+bool leveling_is_valid() {
45
+  return
46
+    #if ENABLED(MESH_BED_LEVELING)
47
+      mbl.has_mesh()
48
+    #elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
49
+      !!bilinear_grid_spacing[X_AXIS]
50
+    #elif ENABLED(AUTO_BED_LEVELING_UBL)
51
+      true
52
+    #else // 3POINT, LINEAR
53
+      true
54
+    #endif
55
+  ;
56
+}
57
+
58
+bool leveling_is_active() {
59
+  return
60
+    #if ENABLED(MESH_BED_LEVELING)
61
+      mbl.active()
62
+    #elif ENABLED(AUTO_BED_LEVELING_UBL)
63
+      ubl.state.active
64
+    #else // OLDSCHOOL_ABL
65
+      planner.abl_enabled
66
+    #endif
67
+  ;
68
+}
69
+
70
+/**
71
+ * Turn bed leveling on or off, fixing the current
72
+ * position as-needed.
73
+ *
74
+ * Disable: Current position = physical position
75
+ *  Enable: Current position = "unleveled" physical position
76
+ */
77
+void set_bed_leveling_enabled(const bool enable/*=true*/) {
78
+
79
+  #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
80
+    const bool can_change = (!enable || leveling_is_valid());
81
+  #else
82
+    constexpr bool can_change = true;
83
+  #endif
84
+
85
+  if (can_change && enable != leveling_is_active()) {
86
+
87
+    #if ENABLED(MESH_BED_LEVELING)
88
+
89
+      if (!enable)
90
+        planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]);
91
+
92
+      const bool enabling = enable && leveling_is_valid();
93
+      mbl.set_active(enabling);
94
+      if (enabling) planner.unapply_leveling(current_position);
95
+
96
+    #elif ENABLED(AUTO_BED_LEVELING_UBL)
97
+      #if PLANNER_LEVELING
98
+        if (ubl.state.active) {                       // leveling from on to off
99
+          // change unleveled current_position to physical current_position without moving steppers.
100
+          planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]);
101
+          ubl.state.active = false;                   // disable only AFTER calling apply_leveling
102
+        }
103
+        else {                                        // leveling from off to on
104
+          ubl.state.active = true;                    // enable BEFORE calling unapply_leveling, otherwise ignored
105
+          // change physical current_position to unleveled current_position without moving steppers.
106
+          planner.unapply_leveling(current_position);
107
+        }
108
+      #else
109
+        ubl.state.active = enable;                    // just flip the bit, current_position will be wrong until next move.
110
+      #endif
111
+
112
+    #else // OLDSCHOOL_ABL
113
+
114
+      #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
115
+        // Force bilinear_z_offset to re-calculate next time
116
+        const float reset[XYZ] = { -9999.999, -9999.999, 0 };
117
+        (void)bilinear_z_offset(reset);
118
+      #endif
119
+
120
+      // Enable or disable leveling compensation in the planner
121
+      planner.abl_enabled = enable;
122
+
123
+      if (!enable)
124
+        // When disabling just get the current position from the steppers.
125
+        // This will yield the smallest error when first converted back to steps.
126
+        set_current_from_steppers_for_axis(
127
+          #if ABL_PLANAR
128
+            ALL_AXES
129
+          #else
130
+            Z_AXIS
131
+          #endif
132
+        );
133
+      else
134
+        // When enabling, remove compensation from the current position,
135
+        // so compensation will give the right stepper counts.
136
+        planner.unapply_leveling(current_position);
137
+
138
+    #endif // OLDSCHOOL_ABL
139
+  }
140
+}
141
+
142
+#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
143
+
144
+  void set_z_fade_height(const float zfh) {
145
+
146
+    const bool level_active = leveling_is_active();
147
+
148
+    #if ENABLED(AUTO_BED_LEVELING_UBL)
149
+
150
+      if (level_active)
151
+        set_bed_leveling_enabled(false);  // turn off before changing fade height for proper apply/unapply leveling to maintain current_position
152
+      planner.z_fade_height = zfh;
153
+      planner.inverse_z_fade_height = RECIPROCAL(zfh);
154
+      if (level_active)
155
+        set_bed_leveling_enabled(true);  // turn back on after changing fade height
156
+
157
+    #else
158
+
159
+      planner.z_fade_height = zfh;
160
+      planner.inverse_z_fade_height = RECIPROCAL(zfh);
161
+
162
+      if (level_active) {
163
+        set_current_from_steppers_for_axis(
164
+          #if ABL_PLANAR
165
+            ALL_AXES
166
+          #else
167
+            Z_AXIS
168
+          #endif
169
+        );
170
+      }
171
+    #endif
172
+  }
173
+
174
+#endif // ENABLE_LEVELING_FADE_HEIGHT
175
+
176
+/**
177
+ * Reset calibration results to zero.
178
+ */
179
+void reset_bed_level() {
180
+  set_bed_leveling_enabled(false);
181
+  #if ENABLED(MESH_BED_LEVELING)
182
+    if (leveling_is_valid()) {
183
+      mbl.reset();
184
+      mbl.set_has_mesh(false);
185
+    }
186
+  #else
187
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
188
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("reset_bed_level");
189
+    #endif
190
+    #if ABL_PLANAR
191
+      planner.bed_level_matrix.set_to_identity();
192
+    #elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
193
+      bilinear_start[X_AXIS] = bilinear_start[Y_AXIS] =
194
+      bilinear_grid_spacing[X_AXIS] = bilinear_grid_spacing[Y_AXIS] = 0;
195
+      for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
196
+        for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
197
+          z_values[x][y] = NAN;
198
+    #elif ENABLED(AUTO_BED_LEVELING_UBL)
199
+      ubl.reset();
200
+    #endif
201
+  #endif
202
+}
203
+
204
+#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(MESH_BED_LEVELING)
205
+
206
+  /**
207
+   * Enable to produce output in JSON format suitable
208
+   * for SCAD or JavaScript mesh visualizers.
209
+   *
210
+   * Visualize meshes in OpenSCAD using the included script.
211
+   *
212
+   *   buildroot/shared/scripts/MarlinMesh.scad
213
+   */
214
+  //#define SCAD_MESH_OUTPUT
215
+
216
+  /**
217
+   * Print calibration results for plotting or manual frame adjustment.
218
+   */
219
+  void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, element_2d_fn fn) {
220
+    #ifndef SCAD_MESH_OUTPUT
221
+      for (uint8_t x = 0; x < sx; x++) {
222
+        for (uint8_t i = 0; i < precision + 2 + (x < 10 ? 1 : 0); i++)
223
+          SERIAL_PROTOCOLCHAR(' ');
224
+        SERIAL_PROTOCOL((int)x);
225
+      }
226
+      SERIAL_EOL();
227
+    #endif
228
+    #ifdef SCAD_MESH_OUTPUT
229
+      SERIAL_PROTOCOLLNPGM("measured_z = ["); // open 2D array
230
+    #endif
231
+    for (uint8_t y = 0; y < sy; y++) {
232
+      #ifdef SCAD_MESH_OUTPUT
233
+        SERIAL_PROTOCOLPGM(" [");           // open sub-array
234
+      #else
235
+        if (y < 10) SERIAL_PROTOCOLCHAR(' ');
236
+        SERIAL_PROTOCOL((int)y);
237
+      #endif
238
+      for (uint8_t x = 0; x < sx; x++) {
239
+        SERIAL_PROTOCOLCHAR(' ');
240
+        const float offset = fn(x, y);
241
+        if (!isnan(offset)) {
242
+          if (offset >= 0) SERIAL_PROTOCOLCHAR('+');
243
+          SERIAL_PROTOCOL_F(offset, precision);
244
+        }
245
+        else {
246
+          #ifdef SCAD_MESH_OUTPUT
247
+            for (uint8_t i = 3; i < precision + 3; i++)
248
+              SERIAL_PROTOCOLCHAR(' ');
249
+            SERIAL_PROTOCOLPGM("NAN");
250
+          #else
251
+            for (uint8_t i = 0; i < precision + 3; i++)
252
+              SERIAL_PROTOCOLCHAR(i ? '=' : ' ');
253
+          #endif
254
+        }
255
+        #ifdef SCAD_MESH_OUTPUT
256
+          if (x < sx - 1) SERIAL_PROTOCOLCHAR(',');
257
+        #endif
258
+      }
259
+      #ifdef SCAD_MESH_OUTPUT
260
+        SERIAL_PROTOCOLCHAR(' ');
261
+        SERIAL_PROTOCOLCHAR(']');                     // close sub-array
262
+        if (y < sy - 1) SERIAL_PROTOCOLCHAR(',');
263
+      #endif
264
+      SERIAL_EOL();
265
+    }
266
+    #ifdef SCAD_MESH_OUTPUT
267
+      SERIAL_PROTOCOLPGM("];");                       // close 2D array
268
+    #endif
269
+    SERIAL_EOL();
270
+  }
271
+
272
+#endif // AUTO_BED_LEVELING_BILINEAR || MESH_BED_LEVELING
273
+
274
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
275
+
276
+  void _manual_goto_xy(const float &x, const float &y) {
277
+    const float old_feedrate_mm_s = feedrate_mm_s;
278
+    #if MANUAL_PROBE_HEIGHT > 0
279
+      const float prev_z = current_position[Z_AXIS];
280
+      feedrate_mm_s = homing_feedrate(Z_AXIS);
281
+      current_position[Z_AXIS] = LOGICAL_Z_POSITION(MANUAL_PROBE_HEIGHT);
282
+      line_to_current_position();
283
+    #endif
284
+
285
+    feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
286
+    current_position[X_AXIS] = LOGICAL_X_POSITION(x);
287
+    current_position[Y_AXIS] = LOGICAL_Y_POSITION(y);
288
+    line_to_current_position();
289
+
290
+    #if MANUAL_PROBE_HEIGHT > 0
291
+      feedrate_mm_s = homing_feedrate(Z_AXIS);
292
+      current_position[Z_AXIS] = prev_z; // move back to the previous Z.
293
+      line_to_current_position();
294
+    #endif
295
+
296
+    feedrate_mm_s = old_feedrate_mm_s;
297
+    stepper.synchronize();
298
+
299
+    #if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING)
300
+      lcd_wait_for_move = false;
301
+    #endif
302
+  }
303
+
304
+#endif
305
+
306
+#if HAS_PROBING_PROCEDURE
307
+  void out_of_range_error(const char* p_edge) {
308
+    SERIAL_PROTOCOLPGM("?Probe ");
309
+    serialprintPGM(p_edge);
310
+    SERIAL_PROTOCOLLNPGM(" position out of range.");
311
+  }
312
+#endif
313
+
314
+#endif // HAS_LEVELING

+ 72
- 0
Marlin/src/feature/bedlevel/bedlevel.h View File

@@ -0,0 +1,72 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+#ifndef __BEDLEVEL_H__
24
+#define __BEDLEVEL_H__
25
+
26
+#include "../../inc/MarlinConfig.h"
27
+
28
+#if ENABLED(MESH_BED_LEVELING)
29
+  #include "mbl/mesh_bed_leveling.h"
30
+#elif ENABLED(AUTO_BED_LEVELING_UBL)
31
+  #include "ubl/ubl.h"
32
+#elif HAS_ABL
33
+  #include "abl/abl.h"
34
+#endif
35
+
36
+#if ENABLED(PROBE_MANUALLY)
37
+  extern bool g29_in_progress;
38
+#else
39
+  constexpr bool g29_in_progress = false;
40
+#endif
41
+
42
+bool leveling_is_valid();
43
+bool leveling_is_active();
44
+void set_bed_leveling_enabled(const bool enable=true);
45
+void reset_bed_level();
46
+
47
+#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
48
+  void set_z_fade_height(const float zfh);
49
+#endif
50
+
51
+#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(MESH_BED_LEVELING)
52
+
53
+  #include <stdint.h>
54
+
55
+  typedef float (*element_2d_fn)(const uint8_t, const uint8_t);
56
+
57
+  /**
58
+   * Print calibration results for plotting or manual frame adjustment.
59
+   */
60
+  void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, element_2d_fn fn);
61
+
62
+#endif
63
+
64
+#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
65
+  void _manual_goto_xy(const float &x, const float &y);
66
+#endif
67
+
68
+#if HAS_PROBING_PROCEDURE
69
+  void out_of_range_error(const char* p_edge);
70
+#endif
71
+
72
+#endif // __BEDLEVEL_H__

Marlin/src/feature/mbl/mesh_bed_leveling.cpp → Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp View File

@@ -20,13 +20,14 @@
20 20
  *
21 21
  */
22 22
 
23
-#include "../../inc/MarlinConfig.h"
23
+#include "../../../inc/MarlinConfig.h"
24 24
 
25 25
 #if ENABLED(MESH_BED_LEVELING)
26 26
 
27 27
   #include "mesh_bed_leveling.h"
28 28
 
29
-  #include "../../module/motion.h"
29
+  #include "../../../module/motion.h"
30
+  #include "../../../feature/bedlevel/bedlevel.h"
30 31
 
31 32
   mesh_bed_leveling mbl;
32 33
 
@@ -110,4 +111,13 @@
110 111
     mesh_line_to_destination(fr_mm_s, x_splits, y_splits);
111 112
   }
112 113
 
114
+  void mbl_mesh_report() {
115
+    SERIAL_PROTOCOLLNPGM("Num X,Y: " STRINGIFY(GRID_MAX_POINTS_X) "," STRINGIFY(GRID_MAX_POINTS_Y));
116
+    SERIAL_PROTOCOLPGM("Z offset: "); SERIAL_PROTOCOL_F(mbl.z_offset, 5);
117
+    SERIAL_PROTOCOLLNPGM("\nMeasured points:");
118
+    print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 5,
119
+      [](const uint8_t ix, const uint8_t iy) { return mbl.z_values[ix][iy]; }
120
+    );
121
+  }
122
+
113 123
 #endif // MESH_BED_LEVELING

Marlin/src/feature/mbl/mesh_bed_leveling.h → Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h View File

@@ -23,7 +23,7 @@
23 23
 #ifndef _MESH_BED_LEVELING_H_
24 24
 #define _MESH_BED_LEVELING_H_
25 25
 
26
-#include "../../Marlin.h"
26
+#include "../../../inc/MarlinConfig.h"
27 27
 
28 28
 enum MeshLevelingState {
29 29
   MeshReport,
@@ -120,6 +120,10 @@ public:
120 120
 
121 121
 extern mesh_bed_leveling mbl;
122 122
 
123
+// Support functions, which may be embedded in the class later
124
+
123 125
 void mesh_line_to_destination(const float fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF);
124 126
 
127
+void mbl_mesh_report();
128
+
125 129
 #endif // _MESH_BED_LEVELING_H_

Marlin/src/feature/ubl/ubl.cpp → Marlin/src/feature/bedlevel/ubl/ubl.cpp View File

@@ -20,17 +20,17 @@
20 20
  *
21 21
  */
22 22
 
23
-#include "../../inc/MarlinConfig.h"
23
+#include "../../../inc/MarlinConfig.h"
24 24
 
25 25
 #if ENABLED(AUTO_BED_LEVELING_UBL)
26 26
 
27 27
   #include "ubl.h"
28 28
   unified_bed_leveling ubl;
29 29
 
30
-  #include "../../module/configuration_store.h"
31
-  #include "../../core/serial.h"
32
-  #include "../../module/planner.h"
33
-  #include "../../module/motion.h"
30
+  #include "../../../module/configuration_store.h"
31
+  #include "../../../module/planner.h"
32
+  #include "../../../module/motion.h"
33
+  #include "../../bedlevel/bedlevel.h"
34 34
 
35 35
   #include "math.h"
36 36
 
@@ -78,6 +78,10 @@
78 78
   bool unified_bed_leveling::g26_debug_flag = false,
79 79
        unified_bed_leveling::has_control_of_lcd_panel = false;
80 80
 
81
+  #if ENABLED(ULTRA_LCD)
82
+    bool unified_bed_leveling::lcd_map_control = false;
83
+  #endif
84
+
81 85
   volatile int unified_bed_leveling::encoder_diff;
82 86
 
83 87
   unified_bed_leveling::unified_bed_leveling() {

Marlin/src/feature/ubl/ubl.h → Marlin/src/feature/bedlevel/ubl/ubl.h View File

@@ -23,9 +23,9 @@
23 23
 #ifndef UNIFIED_BED_LEVELING_H
24 24
 #define UNIFIED_BED_LEVELING_H
25 25
 
26
-#include "../../Marlin.h"
27
-#include "../../core/serial.h"
28
-#include "../../module/planner.h"
26
+#include "../../../Marlin.h"
27
+#include "../../../module/planner.h"
28
+#include "../../../module/motion.h"
29 29
 
30 30
 #define UBL_VERSION "1.01"
31 31
 #define UBL_OK false
@@ -57,7 +57,6 @@ enum MeshPointType { INVALID, REAL, SET_IN_BITMAP };
57 57
 
58 58
 char *ftostr43sign(const float&, char);
59 59
 bool ubl_lcd_clicked();
60
-void home_all_axes();
61 60
 
62 61
 extern uint8_t ubl_cnt;
63 62
 
@@ -190,6 +189,10 @@ class unified_bed_leveling {
190 189
 
191 190
     static bool g26_debug_flag, has_control_of_lcd_panel;
192 191
 
192
+    #if ENABLED(ULTRA_LCD)
193
+      static bool lcd_map_control;
194
+    #endif
195
+
193 196
     static volatile int encoder_diff; // Volatile because it's changed at interrupt time.
194 197
 
195 198
     unified_bed_leveling();
@@ -246,12 +249,16 @@ class unified_bed_leveling {
246 249
      */
247 250
     inline static float z_correction_for_x_on_horizontal_mesh_line(const float &lx0, const int x1_i, const int yi) {
248 251
       if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 2) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) {
249
-        serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") );
250
-        SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0);
251
-        SERIAL_ECHOPAIR(",x1_i=", x1_i);
252
-        SERIAL_ECHOPAIR(",yi=", yi);
253
-        SERIAL_CHAR(')');
254
-        SERIAL_EOL();
252
+        #if ENABLED(DEBUG_LEVELING_FEATURE)
253
+          if (DEBUGGING(LEVELING)) {
254
+            serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") );
255
+            SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0);
256
+            SERIAL_ECHOPAIR(",x1_i=", x1_i);
257
+            SERIAL_ECHOPAIR(",yi=", yi);
258
+            SERIAL_CHAR(')');
259
+            SERIAL_EOL();
260
+          }
261
+        #endif
255 262
         return NAN;
256 263
       }
257 264
 
@@ -266,12 +273,16 @@ class unified_bed_leveling {
266 273
     //
267 274
     inline static float z_correction_for_y_on_vertical_mesh_line(const float &ly0, const int xi, const int y1_i) {
268 275
       if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 2)) {
269
-        serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") );
270
-        SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ly0=", ly0);
271
-        SERIAL_ECHOPAIR(", xi=", xi);
272
-        SERIAL_ECHOPAIR(", y1_i=", y1_i);
273
-        SERIAL_CHAR(')');
274
-        SERIAL_EOL();
276
+        #if ENABLED(DEBUG_LEVELING_FEATURE)
277
+          if (DEBUGGING(LEVELING)) {
278
+            serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") );
279
+            SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ly0=", ly0);
280
+            SERIAL_ECHOPAIR(", xi=", xi);
281
+            SERIAL_ECHOPAIR(", y1_i=", y1_i);
282
+            SERIAL_CHAR(')');
283
+            SERIAL_EOL();
284
+          }
285
+        #endif
275 286
         return NAN;
276 287
       }
277 288
 
@@ -390,6 +401,19 @@ class unified_bed_leveling {
390 401
     static bool prepare_segmented_line_to(const float ltarget[XYZE], const float &feedrate);
391 402
     static void line_to_destination_cartesian(const float &fr, uint8_t e);
392 403
 
404
+    #define _CMPZ(a,b) (z_values[a][b] == z_values[a][b+1])
405
+    #define CMPZ(a) (_CMPZ(a, 0) && _CMPZ(a, 1))
406
+    #define ZZER(a) (z_values[a][0] == 0)
407
+
408
+    FORCE_INLINE bool mesh_is_valid() {
409
+      return !(
410
+        (    CMPZ(0) && CMPZ(1) && CMPZ(2) // adjacent z values all equal?
411
+          && ZZER(0) && ZZER(1) && ZZER(2) // all zero at the edge?
412
+        )
413
+        || isnan(z_values[0][0])
414
+      );
415
+    }
416
+
393 417
 }; // class unified_bed_leveling
394 418
 
395 419
 extern unified_bed_leveling ubl;

Marlin/src/feature/ubl/ubl_G29.cpp → Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp View File

@@ -20,20 +20,23 @@
20 20
  *
21 21
  */
22 22
 
23
-#include "../../inc/MarlinConfig.h"
23
+#include "../../../inc/MarlinConfig.h"
24 24
 
25 25
 #if ENABLED(AUTO_BED_LEVELING_UBL)
26 26
 
27 27
   #include "ubl.h"
28 28
 
29
-  #include "../../Marlin.h"
30
-  #include "../../libs/hex_print_routines.h"
31
-  #include "../../module/configuration_store.h"
32
-  #include "../../lcd/ultralcd.h"
33
-  #include "../../module/stepper.h"
34
-  #include "../../module/planner.h"
35
-  #include "../../gcode/parser.h"
36
-  #include "../../libs/least_squares_fit.h"
29
+  #include "../../../Marlin.h"
30
+  #include "../../../libs/hex_print_routines.h"
31
+  #include "../../../module/configuration_store.h"
32
+  #include "../../../lcd/ultralcd.h"
33
+  #include "../../../module/stepper.h"
34
+  #include "../../../module/planner.h"
35
+  #include "../../../module/probe.h"
36
+  #include "../../../gcode/gcode.h"
37
+  #include "../../../gcode/parser.h"
38
+  #include "../../../feature/bedlevel/bedlevel.h"
39
+  #include "../../../libs/least_squares_fit.h"
37 40
 
38 41
   #include <math.h>
39 42
 
@@ -52,11 +55,8 @@
52 55
 
53 56
   extern float meshedit_done;
54 57
   extern long babysteps_done;
55
-  extern float probe_pt(const float &lx, const float &ly, const bool, const uint8_t, const bool=true);
56
-  extern bool set_probe_deployed(bool);
57
-  extern void set_bed_leveling_enabled(bool);
58
-  typedef void (*screenFunc_t)();
59
-  extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0);
58
+  //extern bool set_probe_deployed(bool);
59
+  //extern void set_bed_leveling_enabled(bool);
60 60
 
61 61
   #define SIZE_OF_LITTLE_RAISE 1
62 62
   #define BIG_RAISE_NOT_NEEDED 0
@@ -314,7 +314,7 @@
314 314
     if (axis_unhomed_error()) {
315 315
       const int8_t p_val = parser.intval('P', -1);
316 316
       if (p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J'))
317
-        home_all_axes();
317
+        gcode.home_all_axes();
318 318
     }
319 319
 
320 320
     if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem,
@@ -1515,7 +1515,7 @@
1515 1515
           idle();
1516 1516
         } while (!ubl_lcd_clicked());
1517 1517
 
1518
-        if (!ubl_lcd_map_control) lcd_return_to_status();
1518
+        if (!lcd_map_control) lcd_return_to_status();
1519 1519
 
1520 1520
         // The technique used here generates a race condition for the encoder click.
1521 1521
         // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here.
@@ -1561,7 +1561,7 @@
1561 1561
       LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH);
1562 1562
       SERIAL_ECHOLNPGM("Done Editing Mesh");
1563 1563
 
1564
-      if (ubl_lcd_map_control)
1564
+      if (lcd_map_control)
1565 1565
         lcd_goto_screen(_lcd_ubl_output_map_lcd);
1566 1566
       else
1567 1567
         lcd_return_to_status();
@@ -1606,7 +1606,7 @@
1606 1606
     //   { GRID_MAX_POINTS_X - 1, 0,  0, GRID_MAX_POINTS_Y,      true  } PROGMEM   // Right side of the mesh looking left
1607 1607
     // };
1608 1608
     for (uint8_t i = 0; i < COUNT(info); ++i) {
1609
-      const smart_fill_info *f = (smart_fill_info*)pgm_read_word(&info[i]);
1609
+      const smart_fill_info *f = (smart_fill_info*)pgm_read_ptr(&info[i]);
1610 1610
       const int8_t sx = pgm_read_word(&f->sx), sy = pgm_read_word(&f->sy),
1611 1611
                    ex = pgm_read_word(&f->ex), ey = pgm_read_word(&f->ey);
1612 1612
       if (pgm_read_byte(&f->yfirst)) {

Marlin/src/feature/ubl/ubl_motion.cpp → Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp View File

@@ -19,16 +19,20 @@
19 19
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20 20
  *
21 21
  */
22
-#include "../../inc/MarlinConfig.h"
22
+#include "../../../inc/MarlinConfig.h"
23 23
 
24 24
 #if ENABLED(AUTO_BED_LEVELING_UBL)
25 25
 
26 26
   #include "ubl.h"
27 27
 
28
-  #include "../../Marlin.h"
29
-  #include "../../module/planner.h"
30
-  #include "../../module/stepper.h"
31
-  #include "../../module/motion.h"
28
+  #include "../../../Marlin.h"
29
+  #include "../../../module/planner.h"
30
+  #include "../../../module/stepper.h"
31
+  #include "../../../module/motion.h"
32
+
33
+  #if ENABLED(DELTA)
34
+    #include "../../../module/delta.h"
35
+  #endif
32 36
 
33 37
   #include <math.h>
34 38
 
@@ -40,25 +44,6 @@
40 44
     extern void set_current_to_destination();
41 45
   #endif
42 46
 
43
-#if ENABLED(DELTA)
44
-
45
-  extern float delta[ABC],
46
-               endstop_adj[ABC];
47
-
48
-  extern float delta_radius,
49
-               delta_tower_angle_trim[2],
50
-               delta_tower[ABC][2],
51
-               delta_diagonal_rod,
52
-               delta_calibration_radius,
53
-               delta_diagonal_rod_2_tower[ABC],
54
-               delta_segments_per_second,
55
-               delta_clip_start_height;
56
-
57
-  extern float delta_safe_distance_from_top();
58
-
59
-#endif
60
-
61
-
62 47
   static void debug_echo_axis(const AxisEnum axis) {
63 48
     if (current_position[axis] == destination[axis])
64 49
       SERIAL_ECHOPGM("-------------");

+ 0
- 893
Marlin/src/feature/ubl/G26_Mesh_Validation_Tool.cpp View File

@@ -1,893 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-/**
24
- * Marlin Firmware -- G26 - Mesh Validation Tool
25
- */
26
-
27
-#include "../../inc/MarlinConfig.h"
28
-
29
-#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION)
30
-
31
-  #include "ubl.h"
32
-
33
-  #include "../../Marlin.h"
34
-  #include "../../module/planner.h"
35
-  #include "../../module/stepper.h"
36
-  #include "../../module/motion.h"
37
-  #include "../../module/temperature.h"
38
-  #include "../../lcd/ultralcd.h"
39
-  #include "../../gcode/parser.h"
40
-
41
-  #define EXTRUSION_MULTIPLIER 1.0
42
-  #define RETRACTION_MULTIPLIER 1.0
43
-  #define NOZZLE 0.4
44
-  #define FILAMENT 1.75
45
-  #define LAYER_HEIGHT 0.2
46
-  #define PRIME_LENGTH 10.0
47
-  #define BED_TEMP 60.0
48
-  #define HOTEND_TEMP 205.0
49
-  #define OOZE_AMOUNT 0.3
50
-
51
-  #define SIZE_OF_INTERSECTION_CIRCLES 5
52
-  #define SIZE_OF_CROSSHAIRS 3
53
-
54
-  #if SIZE_OF_CROSSHAIRS >= SIZE_OF_INTERSECTION_CIRCLES
55
-    #error "SIZE_OF_CROSSHAIRS must be less than SIZE_OF_INTERSECTION_CIRCLES."
56
-  #endif
57
-
58
-  /**
59
-   *   G26 Mesh Validation Tool
60
-   *
61
-   *   G26 is a Mesh Validation Tool intended to provide support for the Marlin Unified Bed Leveling System.
62
-   *   In order to fully utilize and benefit from the Marlin Unified Bed Leveling System an accurate Mesh must
63
-   *   be defined. G29 is designed to allow the user to quickly validate the correctness of her Mesh. It will
64
-   *   first heat the bed and nozzle. It will then print lines and circles along the Mesh Cell boundaries and
65
-   *   the intersections of those lines (respectively).
66
-   *
67
-   *   This action allows the user to immediately see where the Mesh is properly defined and where it needs to
68
-   *   be edited. The command will generate the Mesh lines closest to the nozzle's starting position. Alternatively
69
-   *   the user can specify the X and Y position of interest with command parameters. This allows the user to
70
-   *   focus on a particular area of the Mesh where attention is needed.
71
-   *
72
-   *   B #  Bed         Set the Bed Temperature. If not specified, a default of 60 C. will be assumed.
73
-   *
74
-   *   C    Current     When searching for Mesh Intersection points to draw, use the current nozzle location
75
-   *                    as the base for any distance comparison.
76
-   *
77
-   *   D    Disable     Disable the Unified Bed Leveling System. In the normal case the user is invoking this
78
-   *                    command to see how well a Mesh as been adjusted to match a print surface. In order to do
79
-   *                    this the Unified Bed Leveling System is turned on by the G26 command. The D parameter
80
-   *                    alters the command's normal behaviour and disables the Unified Bed Leveling System even if
81
-   *                    it is on.
82
-   *
83
-   *   H #  Hotend      Set the Nozzle Temperature. If not specified, a default of 205 C. will be assumed.
84
-   *
85
-   *   F #  Filament    Used to specify the diameter of the filament being used. If not specified
86
-   *                    1.75mm filament is assumed. If you are not getting acceptable results by using the
87
-   *                    'correct' numbers, you can scale this number up or down a little bit to change the amount
88
-   *                    of filament that is being extruded during the printing of the various lines on the bed.
89
-   *
90
-   *   K    Keep-On     Keep the heaters turned on at the end of the command.
91
-   *
92
-   *   L #  Layer       Layer height. (Height of nozzle above bed)  If not specified .20mm will be used.
93
-   *
94
-   *   O #  Ooooze      How much your nozzle will Ooooze filament while getting in position to print. This
95
-   *                    is over kill, but using this parameter will let you get the very first 'circle' perfect
96
-   *                    so you have a trophy to peel off of the bed and hang up to show how perfectly you have your
97
-   *                    Mesh calibrated. If not specified, a filament length of .3mm is assumed.
98
-   *
99
-   *   P #  Prime       Prime the nozzle with specified length of filament. If this parameter is not
100
-   *                    given, no prime action will take place. If the parameter specifies an amount, that much
101
-   *                    will be purged before continuing. If no amount is specified the command will start
102
-   *                    purging filament until the user provides an LCD Click and then it will continue with
103
-   *                    printing the Mesh. You can carefully remove the spent filament with a needle nose
104
-   *                    pliers while holding the LCD Click wheel in a depressed state. If you do not have
105
-   *                    an LCD, you must specify a value if you use P.
106
-   *
107
-   *   Q #  Multiplier  Retraction Multiplier. Normally not needed. Retraction defaults to 1.0mm and
108
-   *                    un-retraction is at 1.2mm   These numbers will be scaled by the specified amount
109
-   *
110
-   *   R #  Repeat      Prints the number of patterns given as a parameter, starting at the current location.
111
-   *                    If a parameter isn't given, every point will be printed unless G26 is interrupted.
112
-   *                    This works the same way that the UBL G29 P4 R parameter works.
113
-   *
114
-   *                    NOTE:  If you do not have an LCD, you -must- specify R. This is to ensure that you are
115
-   *                    aware that there's some risk associated with printing without the ability to abort in
116
-   *                    cases where mesh point Z value may be inaccurate. As above, if you do not include a
117
-   *                    parameter, every point will be printed.
118
-   *
119
-   *   S #  Nozzle      Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed.
120
-   *
121
-   *   U #  Random      Randomize the order that the circles are drawn on the bed. The search for the closest
122
-   *                    undrawn cicle is still done. But the distance to the location for each circle has a
123
-   *                    random number of the size specified added to it. Specifying S50 will give an interesting
124
-   *                    deviation from the normal behaviour on a 10 x 10 Mesh.
125
-   *
126
-   *   X #  X Coord.    Specify the starting location of the drawing activity.
127
-   *
128
-   *   Y #  Y Coord.    Specify the starting location of the drawing activity.
129
-   */
130
-
131
-  // External references
132
-
133
-  extern Planner planner;
134
-  #if ENABLED(ULTRA_LCD)
135
-    extern char lcd_status_message[];
136
-  #endif
137
-  extern float destination[XYZE];
138
-  extern void set_destination_to_current() { COPY(destination, current_position); }
139
-  void prepare_move_to_destination();
140
-  #if AVR_AT90USB1286_FAMILY  // Teensyduino & Printrboard IDE extensions have compile errors without this
141
-    inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
142
-    inline void set_current_to_destination() { COPY(current_position, destination); }
143
-  #else
144
-    extern void sync_plan_position_e();
145
-    extern void set_current_to_destination();
146
-  #endif
147
-  #if ENABLED(NEWPANEL)
148
-    void lcd_setstatusPGM(const char* const message, const int8_t level);
149
-    void chirp_at_user();
150
-  #endif
151
-
152
-  // Private functions
153
-
154
-  static uint16_t circle_flags[16], horizontal_mesh_line_flags[16], vertical_mesh_line_flags[16];
155
-  float g26_e_axis_feedrate = 0.020,
156
-        random_deviation = 0.0;
157
-
158
-  static bool g26_retracted = false; // Track the retracted state of the nozzle so mismatched
159
-                                     // retracts/recovers won't result in a bad state.
160
-
161
-  float valid_trig_angle(float);
162
-
163
-  float unified_bed_leveling::g26_extrusion_multiplier,
164
-        unified_bed_leveling::g26_retraction_multiplier,
165
-        unified_bed_leveling::g26_nozzle,
166
-        unified_bed_leveling::g26_filament_diameter,
167
-        unified_bed_leveling::g26_layer_height,
168
-        unified_bed_leveling::g26_prime_length,
169
-        unified_bed_leveling::g26_x_pos,
170
-        unified_bed_leveling::g26_y_pos,
171
-        unified_bed_leveling::g26_ooze_amount;
172
-
173
-  int16_t unified_bed_leveling::g26_bed_temp,
174
-          unified_bed_leveling::g26_hotend_temp;
175
-
176
-  int8_t unified_bed_leveling::g26_prime_flag;
177
-
178
-  bool unified_bed_leveling::g26_continue_with_closest,
179
-       unified_bed_leveling::g26_keep_heaters_on;
180
-
181
-  int16_t unified_bed_leveling::g26_repeats;
182
-
183
-  void unified_bed_leveling::G26_line_to_destination(const float &feed_rate) {
184
-    const float save_feedrate = feedrate_mm_s;
185
-    feedrate_mm_s = feed_rate;      // use specified feed rate
186
-    prepare_move_to_destination();  // will ultimately call ubl.line_to_destination_cartesian or ubl.prepare_linear_move_to for UBL_DELTA
187
-    feedrate_mm_s = save_feedrate;  // restore global feed rate
188
-  }
189
-
190
-  #if ENABLED(NEWPANEL)
191
-    /**
192
-     * Detect ubl_lcd_clicked, debounce it, and return true for cancel
193
-     */
194
-    bool user_canceled() {
195
-      if (!ubl_lcd_clicked()) return false;
196
-      safe_delay(10);                       // Wait for click to settle
197
-
198
-      #if ENABLED(ULTRA_LCD)
199
-        lcd_setstatusPGM(PSTR("Mesh Validation Stopped."), 99);
200
-        lcd_quick_feedback();
201
-      #endif
202
-
203
-      while (!ubl_lcd_clicked()) idle();    // Wait for button release
204
-
205
-      // If the button is suddenly pressed again,
206
-      // ask the user to resolve the issue
207
-      lcd_setstatusPGM(PSTR("Release button"), 99); // will never appear...
208
-      while (ubl_lcd_clicked()) idle();             // unless this loop happens
209
-      lcd_reset_status();
210
-
211
-      return true;
212
-    }
213
-  #endif
214
-
215
-  /**
216
-   * G26: Mesh Validation Pattern generation.
217
-   *
218
-   * Used to interactively edit UBL's Mesh by placing the
219
-   * nozzle in a problem area and doing a G29 P4 R command.
220
-   */
221
-  void unified_bed_leveling::G26() {
222
-    SERIAL_ECHOLNPGM("G26 command started. Waiting for heater(s).");
223
-    float tmp, start_angle, end_angle;
224
-    int   i, xi, yi;
225
-    mesh_index_pair location;
226
-
227
-    // Don't allow Mesh Validation without homing first,
228
-    // or if the parameter parsing did not go OK, abort
229
-    if (axis_unhomed_error() || parse_G26_parameters()) return;
230
-
231
-    if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) {
232
-      do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
233
-      stepper.synchronize();
234
-      set_current_to_destination();
235
-    }
236
-
237
-    if (turn_on_heaters()) goto LEAVE;
238
-
239
-    current_position[E_AXIS] = 0.0;
240
-    sync_plan_position_e();
241
-
242
-    if (g26_prime_flag && prime_nozzle()) goto LEAVE;
243
-
244
-    /**
245
-     *  Bed is preheated
246
-     *
247
-     *  Nozzle is at temperature
248
-     *
249
-     *  Filament is primed!
250
-     *
251
-     *  It's  "Show Time" !!!
252
-     */
253
-
254
-    ZERO(circle_flags);
255
-    ZERO(horizontal_mesh_line_flags);
256
-    ZERO(vertical_mesh_line_flags);
257
-
258
-    // Move nozzle to the specified height for the first layer
259
-    set_destination_to_current();
260
-    destination[Z_AXIS] = g26_layer_height;
261
-    move_to(destination, 0.0);
262
-    move_to(destination, g26_ooze_amount);
263
-
264
-    has_control_of_lcd_panel = true;
265
-    //debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern."));
266
-
267
-    /**
268
-     * Declare and generate a sin() & cos() table to be used during the circle drawing. This will lighten
269
-     * the CPU load and make the arc drawing faster and more smooth
270
-     */
271
-    float sin_table[360 / 30 + 1], cos_table[360 / 30 + 1];
272
-    for (i = 0; i <= 360 / 30; i++) {
273
-      cos_table[i] = SIZE_OF_INTERSECTION_CIRCLES * cos(RADIANS(valid_trig_angle(i * 30.0)));
274
-      sin_table[i] = SIZE_OF_INTERSECTION_CIRCLES * sin(RADIANS(valid_trig_angle(i * 30.0)));
275
-    }
276
-
277
-    do {
278
-      location = g26_continue_with_closest
279
-        ? find_closest_circle_to_print(current_position[X_AXIS], current_position[Y_AXIS])
280
-        : find_closest_circle_to_print(g26_x_pos, g26_y_pos); // Find the closest Mesh Intersection to where we are now.
281
-
282
-      if (location.x_index >= 0 && location.y_index >= 0) {
283
-        const float circle_x = mesh_index_to_xpos(location.x_index),
284
-                    circle_y = mesh_index_to_ypos(location.y_index);
285
-
286
-        // If this mesh location is outside the printable_radius, skip it.
287
-
288
-        if (!position_is_reachable_raw_xy(circle_x, circle_y)) continue;
289
-
290
-        xi = location.x_index;  // Just to shrink the next few lines and make them easier to understand
291
-        yi = location.y_index;
292
-
293
-        if (g26_debug_flag) {
294
-          SERIAL_ECHOPAIR("   Doing circle at: (xi=", xi);
295
-          SERIAL_ECHOPAIR(", yi=", yi);
296
-          SERIAL_CHAR(')');
297
-          SERIAL_EOL();
298
-        }
299
-
300
-        start_angle = 0.0;    // assume it is going to be a full circle
301
-        end_angle   = 360.0;
302
-        if (xi == 0) {       // Check for bottom edge
303
-          start_angle = -90.0;
304
-          end_angle   =  90.0;
305
-          if (yi == 0)        // it is an edge, check for the two left corners
306
-            start_angle = 0.0;
307
-          else if (yi == GRID_MAX_POINTS_Y - 1)
308
-            end_angle = 0.0;
309
-        }
310
-        else if (xi == GRID_MAX_POINTS_X - 1) { // Check for top edge
311
-          start_angle =  90.0;
312
-          end_angle   = 270.0;
313
-          if (yi == 0)                  // it is an edge, check for the two right corners
314
-            end_angle = 180.0;
315
-          else if (yi == GRID_MAX_POINTS_Y - 1)
316
-            start_angle = 180.0;
317
-        }
318
-        else if (yi == 0) {
319
-          start_angle =   0.0;         // only do the top   side of the cirlce
320
-          end_angle   = 180.0;
321
-        }
322
-        else if (yi == GRID_MAX_POINTS_Y - 1) {
323
-          start_angle = 180.0;         // only do the bottom side of the cirlce
324
-          end_angle   = 360.0;
325
-        }
326
-
327
-        for (tmp = start_angle; tmp < end_angle - 0.1; tmp += 30.0) {
328
-
329
-          #if ENABLED(NEWPANEL)
330
-            if (user_canceled()) goto LEAVE;              // Check if the user wants to stop the Mesh Validation
331
-          #endif
332
-
333
-          int tmp_div_30 = tmp / 30.0;
334
-          if (tmp_div_30 < 0) tmp_div_30 += 360 / 30;
335
-          if (tmp_div_30 > 11) tmp_div_30 -= 360 / 30;
336
-
337
-          float x = circle_x + cos_table[tmp_div_30],    // for speed, these are now a lookup table entry
338
-                y = circle_y + sin_table[tmp_div_30],
339
-                xe = circle_x + cos_table[tmp_div_30 + 1],
340
-                ye = circle_y + sin_table[tmp_div_30 + 1];
341
-          #if IS_KINEMATIC
342
-            // Check to make sure this segment is entirely on the bed, skip if not.
343
-            if (!position_is_reachable_raw_xy(x, y) || !position_is_reachable_raw_xy(xe, ye)) continue;
344
-          #else                                              // not, we need to skip
345
-            x  = constrain(x, X_MIN_POS + 1, X_MAX_POS - 1); // This keeps us from bumping the endstops
346
-            y  = constrain(y, Y_MIN_POS + 1, Y_MAX_POS - 1);
347
-            xe = constrain(xe, X_MIN_POS + 1, X_MAX_POS - 1);
348
-            ye = constrain(ye, Y_MIN_POS + 1, Y_MAX_POS - 1);
349
-          #endif
350
-
351
-          //if (g26_debug_flag) {
352
-          //  char ccc, *cptr, seg_msg[50], seg_num[10];
353
-          //  strcpy(seg_msg, "   segment: ");
354
-          //  strcpy(seg_num, "    \n");
355
-          //  cptr = (char*) "01234567890ABCDEF????????";
356
-          //  ccc = cptr[tmp_div_30];
357
-          //  seg_num[1] = ccc;
358
-          //  strcat(seg_msg, seg_num);
359
-          //  debug_current_and_destination(seg_msg);
360
-          //}
361
-
362
-          print_line_from_here_to_there(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), g26_layer_height, LOGICAL_X_POSITION(xe), LOGICAL_Y_POSITION(ye), g26_layer_height);
363
-
364
-        }
365
-        if (look_for_lines_to_connect())
366
-          goto LEAVE;
367
-      }
368
-    } while (--g26_repeats && location.x_index >= 0 && location.y_index >= 0);
369
-
370
-    LEAVE:
371
-    lcd_setstatusPGM(PSTR("Leaving G26"), -1);
372
-
373
-    retract_filament(destination);
374
-    destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;
375
-
376
-    //debug_current_and_destination(PSTR("ready to do Z-Raise."));
377
-    move_to(destination, 0); // Raise the nozzle
378
-    //debug_current_and_destination(PSTR("done doing Z-Raise."));
379
-
380
-    destination[X_AXIS] = g26_x_pos;                                               // Move back to the starting position
381
-    destination[Y_AXIS] = g26_y_pos;
382
-    //destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;                        // Keep the nozzle where it is
383
-
384
-    move_to(destination, 0); // Move back to the starting position
385
-    //debug_current_and_destination(PSTR("done doing X/Y move."));
386
-
387
-    has_control_of_lcd_panel = false;     // Give back control of the LCD Panel!
388
-
389
-    if (!g26_keep_heaters_on) {
390
-      #if HAS_TEMP_BED
391
-        thermalManager.setTargetBed(0);
392
-      #endif
393
-      thermalManager.setTargetHotend(0, 0);
394
-    }
395
-  }
396
-
397
-  float valid_trig_angle(float d) {
398
-    while (d > 360.0) d -= 360.0;
399
-    while (d < 0.0) d += 360.0;
400
-    return d;
401
-  }
402
-
403
-  mesh_index_pair unified_bed_leveling::find_closest_circle_to_print(const float &X, const float &Y) {
404
-    float closest = 99999.99;
405
-    mesh_index_pair return_val;
406
-
407
-    return_val.x_index = return_val.y_index = -1;
408
-
409
-    for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) {
410
-      for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
411
-        if (!is_bit_set(circle_flags, i, j)) {
412
-          const float mx = mesh_index_to_xpos(i),  // We found a circle that needs to be printed
413
-                      my = mesh_index_to_ypos(j);
414
-
415
-          // Get the distance to this intersection
416
-          float f = HYPOT(X - mx, Y - my);
417
-
418
-          // It is possible that we are being called with the values
419
-          // to let us find the closest circle to the start position.
420
-          // But if this is not the case, add a small weighting to the
421
-          // distance calculation to help it choose a better place to continue.
422
-          f += HYPOT(g26_x_pos - mx, g26_y_pos - my) / 15.0;
423
-
424
-          // Add in the specified amount of Random Noise to our search
425
-          if (random_deviation > 1.0)
426
-            f += random(0.0, random_deviation);
427
-
428
-          if (f < closest) {
429
-            closest = f;              // We found a closer location that is still
430
-            return_val.x_index = i;   // un-printed  --- save the data for it
431
-            return_val.y_index = j;
432
-            return_val.distance = closest;
433
-          }
434
-        }
435
-      }
436
-    }
437
-    bit_set(circle_flags, return_val.x_index, return_val.y_index);   // Mark this location as done.
438
-    return return_val;
439
-  }
440
-
441
-  bool unified_bed_leveling::look_for_lines_to_connect() {
442
-    float sx, sy, ex, ey;
443
-
444
-    for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) {
445
-      for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
446
-
447
-        #if ENABLED(NEWPANEL)
448
-          if (user_canceled()) return true;     // Check if the user wants to stop the Mesh Validation
449
-        #endif
450
-
451
-        if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X.
452
-                                     // This is already a half circle because we are at the edge of the bed.
453
-
454
-          if (is_bit_set(circle_flags, i, j) && is_bit_set(circle_flags, i + 1, j)) { // check if we can do a line to the left
455
-            if (!is_bit_set(horizontal_mesh_line_flags, i, j)) {
456
-
457
-              //
458
-              // We found two circles that need a horizontal line to connect them
459
-              // Print it!
460
-              //
461
-              sx = mesh_index_to_xpos(  i  ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // right edge
462
-              ex = mesh_index_to_xpos(i + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // left edge
463
-
464
-              sx = constrain(sx, X_MIN_POS + 1, X_MAX_POS - 1);
465
-              sy = ey = constrain(mesh_index_to_ypos(j), Y_MIN_POS + 1, Y_MAX_POS - 1);
466
-              ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1);
467
-
468
-              if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) {
469
-
470
-                if (g26_debug_flag) {
471
-                  SERIAL_ECHOPAIR(" Connecting with horizontal line (sx=", sx);
472
-                  SERIAL_ECHOPAIR(", sy=", sy);
473
-                  SERIAL_ECHOPAIR(") -> (ex=", ex);
474
-                  SERIAL_ECHOPAIR(", ey=", ey);
475
-                  SERIAL_CHAR(')');
476
-                  SERIAL_EOL();
477
-                  //debug_current_and_destination(PSTR("Connecting horizontal line."));
478
-                }
479
-
480
-                print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height);
481
-              }
482
-              bit_set(horizontal_mesh_line_flags, i, j);   // Mark it as done so we don't do it again, even if we skipped it
483
-            }
484
-          }
485
-
486
-          if (j < GRID_MAX_POINTS_Y) { // We can't connect to anything further back than GRID_MAX_POINTS_Y.
487
-                                           // This is already a half circle because we are at the edge  of the bed.
488
-
489
-            if (is_bit_set(circle_flags, i, j) && is_bit_set(circle_flags, i, j + 1)) { // check if we can do a line straight down
490
-              if (!is_bit_set( vertical_mesh_line_flags, i, j)) {
491
-                //
492
-                // We found two circles that need a vertical line to connect them
493
-                // Print it!
494
-                //
495
-                sy = mesh_index_to_ypos(  j  ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // top edge
496
-                ey = mesh_index_to_ypos(j + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // bottom edge
497
-
498
-                sx = ex = constrain(mesh_index_to_xpos(i), X_MIN_POS + 1, X_MAX_POS - 1);
499
-                sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1);
500
-                ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1);
501
-
502
-                if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) {
503
-
504
-                  if (g26_debug_flag) {
505
-                    SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx);
506
-                    SERIAL_ECHOPAIR(", sy=", sy);
507
-                    SERIAL_ECHOPAIR(") -> (ex=", ex);
508
-                    SERIAL_ECHOPAIR(", ey=", ey);
509
-                    SERIAL_CHAR(')');
510
-                    SERIAL_EOL();
511
-                    debug_current_and_destination(PSTR("Connecting vertical line."));
512
-                  }
513
-                  print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height);
514
-                }
515
-                bit_set(vertical_mesh_line_flags, i, j);   // Mark it as done so we don't do it again, even if skipped
516
-              }
517
-            }
518
-          }
519
-        }
520
-      }
521
-    }
522
-    return false;
523
-  }
524
-
525
-  void unified_bed_leveling::move_to(const float &x, const float &y, const float &z, const float &e_delta) {
526
-    float feed_value;
527
-    static float last_z = -999.99;
528
-
529
-    bool has_xy_component = (x != current_position[X_AXIS] || y != current_position[Y_AXIS]); // Check if X or Y is involved in the movement.
530
-
531
-    if (z != last_z) {
532
-      last_z = z;
533
-      feed_value = planner.max_feedrate_mm_s[Z_AXIS]/(3.0);  // Base the feed rate off of the configured Z_AXIS feed rate
534
-
535
-      destination[X_AXIS] = current_position[X_AXIS];
536
-      destination[Y_AXIS] = current_position[Y_AXIS];
537
-      destination[Z_AXIS] = z;                          // We know the last_z==z or we wouldn't be in this block of code.
538
-      destination[E_AXIS] = current_position[E_AXIS];
539
-
540
-      G26_line_to_destination(feed_value);
541
-
542
-      stepper.synchronize();
543
-      set_destination_to_current();
544
-    }
545
-
546
-    // Check if X or Y is involved in the movement.
547
-    // Yes: a 'normal' movement. No: a retract() or recover()
548
-    feed_value = has_xy_component ? PLANNER_XY_FEEDRATE() / 10.0 : planner.max_feedrate_mm_s[E_AXIS] / 1.5;
549
-
550
-    if (g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() feed_value for XY:", feed_value);
551
-
552
-    destination[X_AXIS] = x;
553
-    destination[Y_AXIS] = y;
554
-    destination[E_AXIS] += e_delta;
555
-
556
-    G26_line_to_destination(feed_value);
557
-
558
-    stepper.synchronize();
559
-    set_destination_to_current();
560
-
561
-  }
562
-
563
-  void unified_bed_leveling::retract_filament(const float where[XYZE]) {
564
-    if (!g26_retracted) { // Only retract if we are not already retracted!
565
-      g26_retracted = true;
566
-      move_to(where, -1.0 * g26_retraction_multiplier);
567
-    }
568
-  }
569
-
570
-  void unified_bed_leveling::recover_filament(const float where[XYZE]) {
571
-    if (g26_retracted) { // Only un-retract if we are retracted.
572
-      move_to(where, 1.2 * g26_retraction_multiplier);
573
-      g26_retracted = false;
574
-    }
575
-  }
576
-
577
-  /**
578
-   * print_line_from_here_to_there() takes two cartesian coordinates and draws a line from one
579
-   * to the other. But there are really three sets of coordinates involved. The first coordinate
580
-   * is the present location of the nozzle. We don't necessarily want to print from this location.
581
-   * We first need to move the nozzle to the start of line segment where we want to print. Once
582
-   * there, we can use the two coordinates supplied to draw the line.
583
-   *
584
-   * Note:  Although we assume the first set of coordinates is the start of the line and the second
585
-   * set of coordinates is the end of the line, it does not always work out that way. This function
586
-   * optimizes the movement to minimize the travel distance before it can start printing. This saves
587
-   * a lot of time and eliminates a lot of nonsensical movement of the nozzle. However, it does
588
-   * cause a lot of very little short retracement of th nozzle when it draws the very first line
589
-   * segment of a 'circle'. The time this requires is very short and is easily saved by the other
590
-   * cases where the optimization comes into play.
591
-   */
592
-  void unified_bed_leveling::print_line_from_here_to_there(const float &sx, const float &sy, const float &sz, const float &ex, const float &ey, const float &ez) {
593
-    const float dx_s = current_position[X_AXIS] - sx,   // find our distance from the start of the actual line segment
594
-                dy_s = current_position[Y_AXIS] - sy,
595
-                dist_start = HYPOT2(dx_s, dy_s),        // We don't need to do a sqrt(), we can compare the distance^2
596
-                                                        // to save computation time
597
-                dx_e = current_position[X_AXIS] - ex,   // find our distance from the end of the actual line segment
598
-                dy_e = current_position[Y_AXIS] - ey,
599
-                dist_end = HYPOT2(dx_e, dy_e),
600
-
601
-                line_length = HYPOT(ex - sx, ey - sy);
602
-
603
-    // If the end point of the line is closer to the nozzle, flip the direction,
604
-    // moving from the end to the start. On very small lines the optimization isn't worth it.
605
-    if (dist_end < dist_start && (SIZE_OF_INTERSECTION_CIRCLES) < FABS(line_length)) {
606
-      return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz);
607
-    }
608
-
609
-    // Decide whether to retract & bump
610
-
611
-    if (dist_start > 2.0) {
612
-      retract_filament(destination);
613
-      //todo:  parameterize the bump height with a define
614
-      move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + 0.500, 0.0);  // Z bump to minimize scraping
615
-      move_to(sx, sy, sz + 0.500, 0.0); // Get to the starting point with no extrusion while bumped
616
-    }
617
-
618
-    move_to(sx, sy, sz, 0.0); // Get to the starting point with no extrusion / un-Z bump
619
-
620
-    const float e_pos_delta = line_length * g26_e_axis_feedrate * g26_extrusion_multiplier;
621
-
622
-    recover_filament(destination);
623
-    move_to(ex, ey, ez, e_pos_delta);  // Get to the ending point with an appropriate amount of extrusion
624
-  }
625
-
626
-  /**
627
-   * This function used to be inline code in G26. But there are so many
628
-   * parameters it made sense to turn them into static globals and get
629
-   * this code out of sight of the main routine.
630
-   */
631
-  bool unified_bed_leveling::parse_G26_parameters() {
632
-
633
-    g26_extrusion_multiplier  = EXTRUSION_MULTIPLIER;
634
-    g26_retraction_multiplier = RETRACTION_MULTIPLIER;
635
-    g26_nozzle                = NOZZLE;
636
-    g26_filament_diameter     = FILAMENT;
637
-    g26_layer_height          = LAYER_HEIGHT;
638
-    g26_prime_length          = PRIME_LENGTH;
639
-    g26_bed_temp              = BED_TEMP;
640
-    g26_hotend_temp           = HOTEND_TEMP;
641
-    g26_prime_flag            = 0;
642
-
643
-    g26_ooze_amount           = parser.linearval('O', OOZE_AMOUNT);
644
-    g26_keep_heaters_on       = parser.boolval('K');
645
-    g26_continue_with_closest = parser.boolval('C');
646
-
647
-    if (parser.seenval('B')) {
648
-      g26_bed_temp = parser.value_celsius();
649
-      if (!WITHIN(g26_bed_temp, 15, 140)) {
650
-        SERIAL_PROTOCOLLNPGM("?Specified bed temperature not plausible.");
651
-        return UBL_ERR;
652
-      }
653
-    }
654
-
655
-    if (parser.seenval('L')) {
656
-      g26_layer_height = parser.value_linear_units();
657
-      if (!WITHIN(g26_layer_height, 0.0, 2.0)) {
658
-        SERIAL_PROTOCOLLNPGM("?Specified layer height not plausible.");
659
-        return UBL_ERR;
660
-      }
661
-    }
662
-
663
-    if (parser.seen('Q')) {
664
-      if (parser.has_value()) {
665
-        g26_retraction_multiplier = parser.value_float();
666
-        if (!WITHIN(g26_retraction_multiplier, 0.05, 15.0)) {
667
-          SERIAL_PROTOCOLLNPGM("?Specified Retraction Multiplier not plausible.");
668
-          return UBL_ERR;
669
-        }
670
-      }
671
-      else {
672
-        SERIAL_PROTOCOLLNPGM("?Retraction Multiplier must be specified.");
673
-        return UBL_ERR;
674
-      }
675
-    }
676
-
677
-    if (parser.seenval('S')) {
678
-      g26_nozzle = parser.value_float();
679
-      if (!WITHIN(g26_nozzle, 0.1, 1.0)) {
680
-        SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible.");
681
-        return UBL_ERR;
682
-      }
683
-    }
684
-
685
-    if (parser.seen('P')) {
686
-      if (!parser.has_value()) {
687
-        #if ENABLED(NEWPANEL)
688
-          g26_prime_flag = -1;
689
-        #else
690
-          SERIAL_PROTOCOLLNPGM("?Prime length must be specified when not using an LCD.");
691
-          return UBL_ERR;
692
-        #endif
693
-      }
694
-      else {
695
-        g26_prime_flag++;
696
-        g26_prime_length = parser.value_linear_units();
697
-        if (!WITHIN(g26_prime_length, 0.0, 25.0)) {
698
-          SERIAL_PROTOCOLLNPGM("?Specified prime length not plausible.");
699
-          return UBL_ERR;
700
-        }
701
-      }
702
-    }
703
-
704
-    if (parser.seenval('F')) {
705
-      g26_filament_diameter = parser.value_linear_units();
706
-      if (!WITHIN(g26_filament_diameter, 1.0, 4.0)) {
707
-        SERIAL_PROTOCOLLNPGM("?Specified filament size not plausible.");
708
-        return UBL_ERR;
709
-      }
710
-    }
711
-    g26_extrusion_multiplier *= sq(1.75) / sq(g26_filament_diameter); // If we aren't using 1.75mm filament, we need to
712
-                                                                      // scale up or down the length needed to get the
713
-                                                                      // same volume of filament
714
-
715
-    g26_extrusion_multiplier *= g26_filament_diameter * sq(g26_nozzle) / sq(0.3); // Scale up by nozzle size
716
-
717
-    if (parser.seenval('H')) {
718
-      g26_hotend_temp = parser.value_celsius();
719
-      if (!WITHIN(g26_hotend_temp, 165, 280)) {
720
-        SERIAL_PROTOCOLLNPGM("?Specified nozzle temperature not plausible.");
721
-        return UBL_ERR;
722
-      }
723
-    }
724
-
725
-    if (parser.seen('U')) {
726
-      randomSeed(millis());
727
-      // This setting will persist for the next G26
728
-      random_deviation = parser.has_value() ? parser.value_float() : 50.0;
729
-    }
730
-
731
-    #if ENABLED(NEWPANEL)
732
-      g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1);
733
-    #else
734
-      if (!parser.seen('R')) {
735
-        SERIAL_PROTOCOLLNPGM("?(R)epeat must be specified when not using an LCD.");
736
-        return UBL_ERR;
737
-      }
738
-      else
739
-        g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1;
740
-    #endif
741
-    if (g26_repeats < 1) {
742
-      SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be at least 1.");
743
-      return UBL_ERR;
744
-    }
745
-
746
-    g26_x_pos = parser.linearval('X', current_position[X_AXIS]);
747
-    g26_y_pos = parser.linearval('Y', current_position[Y_AXIS]);
748
-    if (!position_is_reachable_xy(g26_x_pos, g26_y_pos)) {
749
-      SERIAL_PROTOCOLLNPGM("?Specified X,Y coordinate out of bounds.");
750
-      return UBL_ERR;
751
-    }
752
-
753
-    /**
754
-     * Wait until all parameters are verified before altering the state!
755
-     */
756
-    set_bed_leveling_enabled(!parser.seen('D'));
757
-
758
-    return UBL_OK;
759
-  }
760
-
761
-  #if ENABLED(NEWPANEL)
762
-    bool unified_bed_leveling::exit_from_g26() {
763
-      lcd_setstatusPGM(PSTR("Leaving G26"), -1);
764
-      while (ubl_lcd_clicked()) idle();
765
-      return UBL_ERR;
766
-    }
767
-  #endif
768
-
769
-  /**
770
-   * Turn on the bed and nozzle heat and
771
-   * wait for them to get up to temperature.
772
-   */
773
-  bool unified_bed_leveling::turn_on_heaters() {
774
-    millis_t next = millis() + 5000UL;
775
-    #if HAS_TEMP_BED
776
-      #if ENABLED(ULTRA_LCD)
777
-        if (g26_bed_temp > 25) {
778
-          lcd_setstatusPGM(PSTR("G26 Heating Bed."), 99);
779
-          lcd_quick_feedback();
780
-      #endif
781
-          has_control_of_lcd_panel = true;
782
-          thermalManager.setTargetBed(g26_bed_temp);
783
-          while (abs(thermalManager.degBed() - g26_bed_temp) > 3) {
784
-
785
-            #if ENABLED(NEWPANEL)
786
-              if (ubl_lcd_clicked()) return exit_from_g26();
787
-            #endif
788
-
789
-            if (ELAPSED(millis(), next)) {
790
-              next = millis() + 5000UL;
791
-              print_heaterstates();
792
-              SERIAL_EOL();
793
-            }
794
-            idle();
795
-          }
796
-      #if ENABLED(ULTRA_LCD)
797
-        }
798
-        lcd_setstatusPGM(PSTR("G26 Heating Nozzle."), 99);
799
-        lcd_quick_feedback();
800
-      #endif
801
-    #endif
802
-
803
-    // Start heating the nozzle and wait for it to reach temperature.
804
-    thermalManager.setTargetHotend(g26_hotend_temp, 0);
805
-    while (abs(thermalManager.degHotend(0) - g26_hotend_temp) > 3) {
806
-
807
-      #if ENABLED(NEWPANEL)
808
-        if (ubl_lcd_clicked()) return exit_from_g26();
809
-      #endif
810
-
811
-      if (ELAPSED(millis(), next)) {
812
-        next = millis() + 5000UL;
813
-        print_heaterstates();
814
-        SERIAL_EOL();
815
-      }
816
-      idle();
817
-    }
818
-
819
-    #if ENABLED(ULTRA_LCD)
820
-      lcd_reset_status();
821
-      lcd_quick_feedback();
822
-    #endif
823
-
824
-    return UBL_OK;
825
-  }
826
-
827
-  /**
828
-   * Prime the nozzle if needed. Return true on error.
829
-   */
830
-  bool unified_bed_leveling::prime_nozzle() {
831
-
832
-    #if ENABLED(NEWPANEL)
833
-      float Total_Prime = 0.0;
834
-
835
-      if (g26_prime_flag == -1) {  // The user wants to control how much filament gets purged
836
-
837
-        has_control_of_lcd_panel = true;
838
-        lcd_setstatusPGM(PSTR("User-Controlled Prime"), 99);
839
-        chirp_at_user();
840
-
841
-        set_destination_to_current();
842
-
843
-        recover_filament(destination); // Make sure G26 doesn't think the filament is retracted().
844
-
845
-        while (!ubl_lcd_clicked()) {
846
-          chirp_at_user();
847
-          destination[E_AXIS] += 0.25;
848
-          #ifdef PREVENT_LENGTHY_EXTRUDE
849
-            Total_Prime += 0.25;
850
-            if (Total_Prime >= EXTRUDE_MAXLENGTH) return UBL_ERR;
851
-          #endif
852
-          G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
853
-
854
-          stepper.synchronize();    // Without this synchronize, the purge is more consistent,
855
-                                    // but because the planner has a buffer, we won't be able
856
-                                    // to stop as quickly. So we put up with the less smooth
857
-                                    // action to give the user a more responsive 'Stop'.
858
-          set_destination_to_current();
859
-          idle();
860
-        }
861
-
862
-        while (ubl_lcd_clicked()) idle();           // Debounce Encoder Wheel
863
-
864
-        #if ENABLED(ULTRA_LCD)
865
-          strcpy_P(lcd_status_message, PSTR("Done Priming")); // We can't do lcd_setstatusPGM() without having it continue;
866
-                                                              // So... We cheat to get a message up.
867
-          lcd_setstatusPGM(PSTR("Done Priming"), 99);
868
-          lcd_quick_feedback();
869
-        #endif
870
-
871
-        has_control_of_lcd_panel = false;
872
-
873
-      }
874
-      else {
875
-    #else
876
-    {
877
-    #endif
878
-      #if ENABLED(ULTRA_LCD)
879
-        lcd_setstatusPGM(PSTR("Fixed Length Prime."), 99);
880
-        lcd_quick_feedback();
881
-      #endif
882
-      set_destination_to_current();
883
-      destination[E_AXIS] += g26_prime_length;
884
-      G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
885
-      stepper.synchronize();
886
-      set_destination_to_current();
887
-      retract_filament(destination);
888
-    }
889
-
890
-    return UBL_OK;
891
-  }
892
-
893
-#endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_VALIDATION

Marlin/src/gcode/calibrate/M420.h → Marlin/src/gcode/bedlevel/M420.cpp View File

@@ -20,6 +20,18 @@
20 20
  *
21 21
  */
22 22
 
23
+#include "../../inc/MarlinConfig.h"
24
+
25
+#if HAS_LEVELING
26
+
27
+#include "../gcode.h"
28
+#include "../../feature/bedlevel/bedlevel.h"
29
+#include "../../module/planner.h"
30
+
31
+#if ENABLED(EEPROM_SETTINGS)
32
+  #include "../../module/configuration_store.h"
33
+#endif
34
+
23 35
 /**
24 36
  * M420: Enable/Disable Bed Leveling and/or set the Z fade height.
25 37
  *
@@ -31,7 +43,7 @@
31 43
  *
32 44
  *   L[index]  Load UBL mesh from index (0 is default)
33 45
  */
34
-void gcode_M420() {
46
+void GcodeSuite::M420() {
35 47
 
36 48
   #if ENABLED(AUTO_BED_LEVELING_UBL)
37 49
 
@@ -64,10 +76,10 @@ void gcode_M420() {
64 76
       #endif
65 77
     }
66 78
 
67
-    // L to load a mesh from the EEPROM
79
+    // L or V display the map info
68 80
     if (parser.seen('L') || parser.seen('V')) {
69 81
       ubl.display_map(0);  // Currently only supports one map type
70
-      SERIAL_ECHOLNPAIR("UBL_MESH_VALID = ", UBL_MESH_VALID);
82
+      SERIAL_ECHOLNPAIR("ubl.mesh_is_valid = ", ubl.mesh_is_valid());
71 83
       SERIAL_ECHOLNPAIR("ubl.state.storage_slot = ", ubl.state.storage_slot);
72 84
     }
73 85
 
@@ -119,3 +131,5 @@ void gcode_M420() {
119 131
       SERIAL_ECHOLNPGM(MSG_OFF);
120 132
   #endif
121 133
 }
134
+
135
+#endif // HAS_LEVELING

Marlin/src/gcode/calibrate/G29-abl.h → Marlin/src/gcode/bedlevel/abl/G29.cpp View File

@@ -20,6 +20,29 @@
20 20
  *
21 21
  */
22 22
 
23
+/**
24
+ * G29.cpp - Auto Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if OLDSCHOOL_ABL
30
+
31
+#include "../../gcode.h"
32
+#include "../../../feature/bedlevel/bedlevel.h"
33
+#include "../../../module/motion.h"
34
+#include "../../../module/planner.h"
35
+#include "../../../module/stepper.h"
36
+#include "../../../module/probe.h"
37
+
38
+#if ENABLED(LCD_BED_LEVELING) && ENABLED(PROBE_MANUALLY)
39
+  #include "../../../lcd/ultralcd.h"
40
+#endif
41
+
42
+#if ENABLED(AUTO_BED_LEVELING_LINEAR)
43
+  #include "../../../libs/least_squares_fit.h"
44
+#endif
45
+
23 46
 #if ABL_GRID
24 47
   #if ENABLED(PROBE_Y_FIRST)
25 48
     #define PR_OUTER_VAR xCount
@@ -106,7 +129,7 @@
106 129
  *     There's no extra effect if you have a fixed Z probe.
107 130
  *
108 131
  */
109
-void gcode_G29() {
132
+void GcodeSuite::G29() {
110 133
 
111 134
   // G29 Q is also available if debugging
112 135
   #if ENABLED(DEBUG_LEVELING_FEATURE)
@@ -176,12 +199,10 @@ void gcode_G29() {
176 199
                         abl_grid_points_y = GRID_MAX_POINTS_Y;
177 200
     #endif
178 201
 
179
-    #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(PROBE_MANUALLY)
180
-      #if ENABLED(AUTO_BED_LEVELING_LINEAR)
181
-        ABL_VAR int abl2;
182
-      #else // Bilinear
183
-        int constexpr abl2 = GRID_MAX_POINTS;
184
-      #endif
202
+    #if ENABLED(AUTO_BED_LEVELING_LINEAR)
203
+      ABL_VAR int abl2;
204
+    #elif ENABLED(PROBE_MANUALLY) // Bilinear
205
+      int constexpr abl2 = GRID_MAX_POINTS;
185 206
     #endif
186 207
 
187 208
     #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
@@ -199,7 +220,9 @@ void gcode_G29() {
199 220
 
200 221
   #elif ENABLED(AUTO_BED_LEVELING_3POINT)
201 222
 
202
-    int constexpr abl2 = 3;
223
+    #if ENABLED(PROBE_MANUALLY)
224
+      int constexpr abl2 = 3; // used to show total points
225
+    #endif
203 226
 
204 227
     // Probe at 3 arbitrary points
205 228
     ABL_VAR vector_3 points[3] = {
@@ -944,3 +967,5 @@ void gcode_G29() {
944 967
   if (planner.abl_enabled)
945 968
     SYNC_PLAN_POSITION_KINEMATIC();
946 969
 }
970
+
971
+#endif // OLDSCHOOL_ABL

Marlin/src/gcode/calibrate/M421-abl.h → Marlin/src/gcode/bedlevel/abl/M421.cpp View File

@@ -21,13 +21,24 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * M421.cpp - Auto Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
30
+
31
+#include "../../gcode.h"
32
+#include "../../../feature/bedlevel/abl/abl.h"
33
+
34
+/**
24 35
  * M421: Set a single Mesh Bed Leveling Z coordinate
25 36
  *
26 37
  * Usage:
27 38
  *   M421 I<xindex> J<yindex> Z<linear>
28 39
  *   M421 I<xindex> J<yindex> Q<offset>
29 40
  */
30
-void gcode_M421() {
41
+void GcodeSuite::M421() {
31 42
   int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1);
32 43
   const bool hasI = ix >= 0,
33 44
              hasJ = iy >= 0,
@@ -49,3 +60,5 @@ void gcode_M421() {
49 60
     #endif
50 61
   }
51 62
 }
63
+
64
+#endif // AUTO_BED_LEVELING_BILINEAR

Marlin/src/gcode/calibrate/G29-mbl.h → Marlin/src/gcode/bedlevel/mbl/G29.cpp View File

@@ -20,26 +20,30 @@
20 20
  *
21 21
  */
22 22
 
23
-#include "../queue.h"
23
+/**
24
+ * G29.cpp - Mesh Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(MESH_BED_LEVELING)
30
+
31
+#include "../../../feature/bedlevel/bedlevel.h"
24 32
 
25
-#include "../../libs/buzzer.h"
26
-#include "../../lcd/ultralcd.h"
33
+#include "../../gcode.h"
34
+#include "../../queue.h"
35
+
36
+#include "../../../libs/buzzer.h"
37
+#include "../../../lcd/ultralcd.h"
38
+#include "../../../module/motion.h"
39
+#include "../../../module/stepper.h"
27 40
 
28 41
 // Save 130 bytes with non-duplication of PSTR
29 42
 void echo_not_entered() { SERIAL_PROTOCOLLNPGM(" not entered."); }
30 43
 
31
-void mbl_mesh_report() {
32
-  SERIAL_PROTOCOLLNPGM("Num X,Y: " STRINGIFY(GRID_MAX_POINTS_X) "," STRINGIFY(GRID_MAX_POINTS_Y));
33
-  SERIAL_PROTOCOLPGM("Z offset: "); SERIAL_PROTOCOL_F(mbl.z_offset, 5);
34
-  SERIAL_PROTOCOLLNPGM("\nMeasured points:");
35
-  print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 5,
36
-    [](const uint8_t ix, const uint8_t iy) { return mbl.z_values[ix][iy]; }
37
-  );
38
-}
39
-
40 44
 void mesh_probing_done() {
41 45
   mbl.set_has_mesh(true);
42
-  home_all_axes();
46
+  gcode.home_all_axes();
43 47
   set_bed_leveling_enabled(true);
44 48
   #if ENABLED(MESH_G28_REST_ORIGIN)
45 49
     current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS);
@@ -70,7 +74,7 @@ void mesh_probing_done() {
70 74
  *  v Y-axis  1-n
71 75
  *
72 76
  */
73
-void gcode_G29() {
77
+void GcodeSuite::G29() {
74 78
 
75 79
   static int mbl_probe_index = -1;
76 80
   #if HAS_SOFTWARE_ENDSTOPS
@@ -200,3 +204,5 @@ void gcode_G29() {
200 204
 
201 205
   report_current_position();
202 206
 }
207
+
208
+#endif // MESH_BED_LEVELING

Marlin/src/gcode/calibrate/M421-mbl.h → Marlin/src/gcode/bedlevel/mbl/M421.cpp View File

@@ -21,6 +21,18 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * M421.cpp - Mesh Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(MESH_BED_LEVELING)
30
+
31
+#include "../../gcode.h"
32
+#include "../../../module/motion.h"
33
+#include "../../../feature/bedlevel/mbl/mesh_bed_leveling.h"
34
+
35
+/**
24 36
  * M421: Set a single Mesh Bed Leveling Z coordinate
25 37
  *
26 38
  * Usage:
@@ -29,7 +41,7 @@
29 41
  *   M421 I<xindex> J<yindex> Z<linear>
30 42
  *   M421 I<xindex> J<yindex> Q<offset>
31 43
  */
32
-void gcode_M421() {
44
+void GcodeSuite::M421() {
33 45
   const bool hasX = parser.seen('X'), hasI = parser.seen('I');
34 46
   const int8_t ix = hasI ? parser.value_int() : hasX ? mbl.probe_index_x(RAW_X_POSITION(parser.value_linear_units())) : -1;
35 47
   const bool hasY = parser.seen('Y'), hasJ = parser.seen('J');
@@ -47,3 +59,5 @@ void gcode_M421() {
47 59
   else
48 60
     mbl.set_z(ix, iy, parser.value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0));
49 61
 }
62
+
63
+#endif // MESH_BED_LEVELING

Marlin/src/gcode/calibrate/G29-ubl.h → Marlin/src/gcode/bedlevel/ubl/G26.cpp View File

@@ -20,8 +20,17 @@
20 20
  *
21 21
  */
22 22
 
23
-void gcode_G29() {
23
+/**
24
+ * G26.cpp - Unified Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(UBL_G26_MESH_VALIDATION)
30
+
31
+#include "../../gcode.h"
32
+#include "../../../feature/bedlevel/ubl/ubl.h"
24 33
 
25
-  ubl.G29();
34
+void GcodeSuite::G26() { ubl.G26(); }
26 35
 
27
-}
36
+#endif // UBL_G26_MESH_VALIDATION

Marlin/src/gcode/calibrate/G26.h → Marlin/src/gcode/bedlevel/ubl/G29.cpp View File

@@ -20,8 +20,17 @@
20 20
  *
21 21
  */
22 22
 
23
-void gcode_G26() {
23
+/**
24
+ * G29.cpp - Unified Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(AUTO_BED_LEVELING_UBL)
30
+
31
+#include "../../gcode.h"
32
+#include "../../../feature/bedlevel/ubl/ubl.h"
24 33
 
25
-  ubl.G26();
34
+void GcodeSuite::G29() { ubl.G29(); }
26 35
 
27
-}
36
+#endif // AUTO_BED_LEVELING_UBL

Marlin/src/gcode/calibrate/M421-ubl.h → Marlin/src/gcode/bedlevel/ubl/M421.cpp View File

@@ -21,6 +21,17 @@
21 21
  */
22 22
 
23 23
 /**
24
+ * unified.cpp - Unified Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(AUTO_BED_LEVELING_UBL)
30
+
31
+#include "../../gcode.h"
32
+#include "../../../feature/bedlevel/ubl/ubl.h"
33
+
34
+/**
24 35
  * M421: Set a single Mesh Bed Leveling Z coordinate
25 36
  *
26 37
  * Usage:
@@ -29,7 +40,7 @@
29 40
  *   M421 C Z<linear>
30 41
  *   M421 C Q<offset>
31 42
  */
32
-void gcode_M421() {
43
+void GcodeSuite::M421() {
33 44
   int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1);
34 45
   const bool hasI = ix >= 0,
35 46
              hasJ = iy >= 0,
@@ -54,3 +65,5 @@ void gcode_M421() {
54 65
   else
55 66
     ubl.z_values[ix][iy] = parser.value_linear_units() + (hasQ ? ubl.z_values[ix][iy] : 0);
56 67
 }
68
+
69
+#endif // AUTO_BED_LEVELING_UBL

Marlin/src/gcode/calibrate/M49.h → Marlin/src/gcode/bedlevel/ubl/M49.cpp View File

@@ -20,8 +20,21 @@
20 20
  *
21 21
  */
22 22
 
23
-void gcode_M49() {
23
+/**
24
+ * M49.cpp - Unified Bed Leveling
25
+ */
26
+
27
+#include "../../../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(UBL_G26_MESH_VALIDATION)
30
+
31
+#include "../../gcode.h"
32
+#include "../../../feature/bedlevel/bedlevel.h"
33
+
34
+void GcodeSuite::M49() {
24 35
   ubl.g26_debug_flag ^= true;
25 36
   SERIAL_PROTOCOLPGM("UBL Debug Flag turned ");
26 37
   serialprintPGM(ubl.g26_debug_flag ? PSTR("on.") : PSTR("off."));
27 38
 }
39
+
40
+#endif // UBL_G26_MESH_VALIDATION

Marlin/src/gcode/calibrate/G28.h → Marlin/src/gcode/calibrate/G28.cpp View File

@@ -20,12 +20,23 @@
20 20
  *
21 21
  */
22 22
 
23
-#include "common.h"
23
+#include "../../inc/MarlinConfig.h"
24
+
25
+#include "../gcode.h"
26
+
27
+#include "../../module/stepper.h"
28
+#include "../../module/endstops.h"
24 29
 
25 30
 #if HOTENDS > 1
26
-  #include "../control/tool_change.h"
31
+  #include "../../module/tool_change.h"
27 32
 #endif
28 33
 
34
+#if HAS_LEVELING
35
+  #include "../../feature/bedlevel/bedlevel.h"
36
+#endif
37
+
38
+#include "../../lcd/ultralcd.h"
39
+
29 40
 #if ENABLED(QUICK_HOME)
30 41
 
31 42
   static void quick_home_xy() {
@@ -126,11 +137,11 @@
126 137
  *  Z   Home to the Z endstop
127 138
  *
128 139
  */
129
-void gcode_G28(const bool always_home_all) {
140
+void GcodeSuite::G28(const bool always_home_all) {
130 141
 
131 142
   #if ENABLED(DEBUG_LEVELING_FEATURE)
132 143
     if (DEBUGGING(LEVELING)) {
133
-      SERIAL_ECHOLNPGM(">>> gcode_G28");
144
+      SERIAL_ECHOLNPGM(">>> G28");
134 145
       log_machine_info();
135 146
     }
136 147
   #endif
@@ -288,7 +299,7 @@ void gcode_G28(const bool always_home_all) {
288 299
 
289 300
     SYNC_PLAN_POSITION_KINEMATIC();
290 301
 
291
-  #endif // !DELTA (gcode_G28)
302
+  #endif // !DELTA (G28)
292 303
 
293 304
   endstops.not_homing();
294 305
 
@@ -319,6 +330,6 @@ void gcode_G28(const bool always_home_all) {
319 330
   report_current_position();
320 331
 
321 332
   #if ENABLED(DEBUG_LEVELING_FEATURE)
322
-    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< gcode_G28");
333
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< G28");
323 334
   #endif
324 335
 }

+ 0
- 65
Marlin/src/gcode/calibrate/G29.h View File

@@ -1,65 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
24
-
25
-  #if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING)
26
-    extern bool lcd_wait_for_move;
27
-  #endif
28
-
29
-  inline void _manual_goto_xy(const float &x, const float &y) {
30
-    const float old_feedrate_mm_s = feedrate_mm_s;
31
-    #if MANUAL_PROBE_HEIGHT > 0
32
-      const float prev_z = current_position[Z_AXIS];
33
-      feedrate_mm_s = homing_feedrate(Z_AXIS);
34
-      current_position[Z_AXIS] = LOGICAL_Z_POSITION(MANUAL_PROBE_HEIGHT);
35
-      line_to_current_position();
36
-    #endif
37
-
38
-    feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
39
-    current_position[X_AXIS] = LOGICAL_X_POSITION(x);
40
-    current_position[Y_AXIS] = LOGICAL_Y_POSITION(y);
41
-    line_to_current_position();
42
-
43
-    #if MANUAL_PROBE_HEIGHT > 0
44
-      feedrate_mm_s = homing_feedrate(Z_AXIS);
45
-      current_position[Z_AXIS] = prev_z; // move back to the previous Z.
46
-      line_to_current_position();
47
-    #endif
48
-
49
-    feedrate_mm_s = old_feedrate_mm_s;
50
-    stepper.synchronize();
51
-
52
-    #if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING)
53
-      lcd_wait_for_move = false;
54
-    #endif
55
-  }
56
-
57
-#endif
58
-
59
-#if ENABLED(MESH_BED_LEVELING)
60
-  #include "G29-mbl.h"
61
-#elif ENABLED(AUTO_BED_LEVELING_UBL)
62
-  #include "G29-ubl.h"
63
-#elif HAS_ABL
64
-  #include "G29-abl.h"
65
-#endif

Marlin/src/gcode/calibrate/G33.h → Marlin/src/gcode/calibrate/G33.cpp View File

@@ -20,10 +20,21 @@
20 20
  *
21 21
  */
22 22
 
23
-#include "common.h"
23
+#include "../../inc/MarlinConfig.h"
24 24
 
25
-#if HOTENDS > 1
26
-  #include "../control/tool_change.h"
25
+#if ENABLED(DELTA_AUTO_CALIBRATION)
26
+
27
+#include "../gcode.h"
28
+#include "../../module/delta.h"
29
+#include "../../module/probe.h"
30
+#include "../../module/motion.h"
31
+#include "../../module/stepper.h"
32
+#include "../../module/endstops.h"
33
+#include "../../module/tool_change.h"
34
+#include "../../lcd/ultralcd.h"
35
+
36
+#if HAS_LEVELING
37
+  #include "../../feature/bedlevel/bedlevel.h"
27 38
 #endif
28 39
 
29 40
 /**
@@ -54,7 +65,7 @@
54 65
  *   E   Engage the probe for each point
55 66
  */
56 67
 
57
-void print_signed_float(const char * const prefix, const float &f) {
68
+static void print_signed_float(const char * const prefix, const float &f) {
58 69
   SERIAL_PROTOCOLPGM("  ");
59 70
   serialprintPGM(prefix);
60 71
   SERIAL_PROTOCOLCHAR(':');
@@ -62,12 +73,12 @@ void print_signed_float(const char * const prefix, const float &f) {
62 73
   SERIAL_PROTOCOL_F(f, 2);
63 74
 }
64 75
 
65
-inline void print_G33_settings(const bool end_stops, const bool tower_angles){ // TODO echo these to LCD ???
76
+static void print_G33_settings(const bool end_stops, const bool tower_angles){ // TODO echo these to LCD ???
66 77
   SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]);
67 78
   if (end_stops) {
68
-    print_signed_float(PSTR("  Ex"), endstop_adj[A_AXIS]);
69
-    print_signed_float(PSTR("Ey"), endstop_adj[B_AXIS]);
70
-    print_signed_float(PSTR("Ez"), endstop_adj[C_AXIS]);
79
+    print_signed_float(PSTR("  Ex"), delta_endstop_adj[A_AXIS]);
80
+    print_signed_float(PSTR("Ey"), delta_endstop_adj[B_AXIS]);
81
+    print_signed_float(PSTR("Ez"), delta_endstop_adj[C_AXIS]);
71 82
     SERIAL_PROTOCOLPAIR("    Radius:", delta_radius);
72 83
   }
73 84
   SERIAL_EOL();
@@ -79,7 +90,7 @@ inline void print_G33_settings(const bool end_stops, const bool tower_angles){ /
79 90
   }
80 91
 }
81 92
 
82
-void G33_cleanup(
93
+static void G33_cleanup(
83 94
   #if HOTENDS > 1
84 95
     const uint8_t old_tool_index
85 96
   #endif
@@ -94,7 +105,7 @@ void G33_cleanup(
94 105
   #endif
95 106
 }
96 107
 
97
-void gcode_G33() {
108
+void GcodeSuite::G33() {
98 109
 
99 110
   const int8_t probe_points = parser.intval('P', DELTA_CALIBRATION_DEFAULT_POINTS);
100 111
   if (!WITHIN(probe_points, 1, 7)) {
@@ -110,7 +121,7 @@ void gcode_G33() {
110 121
 
111 122
   const float calibration_precision = parser.floatval('C');
112 123
   if (calibration_precision < 0) {
113
-    SERIAL_PROTOCOLLNPGM("?(C)alibration precision is implausible (>0).");
124
+    SERIAL_PROTOCOLLNPGM("?(C)alibration precision is implausible (>=0).");
114 125
     return;
115 126
   }
116 127
 
@@ -121,7 +132,6 @@ void gcode_G33() {
121 132
   }
122 133
 
123 134
   const bool towers_set           = parser.boolval('T', true),
124
-             stow_after_each      = parser.boolval('E'),
125 135
              _1p_calibration      = probe_points == 1,
126 136
              _4p_calibration      = probe_points == 2,
127 137
              _4p_towers_points    = _4p_calibration && towers_set,
@@ -133,18 +143,24 @@ void gcode_G33() {
133 143
              _7p_quadruple_circle = probe_points == 7,
134 144
              _7p_multi_circle     = _7p_double_circle || _7p_triple_circle || _7p_quadruple_circle,
135 145
              _7p_intermed_points  = _7p_calibration && !_7p_half_circle;
146
+
147
+  #if DISABLED(PROBE_MANUALLY)
148
+    const bool stow_after_each    = parser.boolval('E');
149
+    const float dx = (X_PROBE_OFFSET_FROM_EXTRUDER),
150
+                dy = (Y_PROBE_OFFSET_FROM_EXTRUDER);
151
+  #endif
152
+
136 153
   const static char save_message[] PROGMEM = "Save with M500 and/or copy to Configuration.h";
137
-  const float dx = (X_PROBE_OFFSET_FROM_EXTRUDER),
138
-              dy = (Y_PROBE_OFFSET_FROM_EXTRUDER);
154
+
139 155
   int8_t iterations = 0;
140 156
   float test_precision,
141 157
         zero_std_dev = (verbose_level ? 999.0 : 0.0), // 0.0 in dry-run mode : forced end
142 158
         zero_std_dev_old = zero_std_dev,
143 159
         zero_std_dev_min = zero_std_dev,
144 160
         e_old[XYZ] = {
145
-          endstop_adj[A_AXIS],
146
-          endstop_adj[B_AXIS],
147
-          endstop_adj[C_AXIS]
161
+          delta_endstop_adj[A_AXIS],
162
+          delta_endstop_adj[B_AXIS],
163
+          delta_endstop_adj[C_AXIS]
148 164
         },
149 165
         dr_old = delta_radius,
150 166
         zh_old = home_offset[Z_AXIS],
@@ -167,6 +183,7 @@ void gcode_G33() {
167 183
   SERIAL_PROTOCOLLNPGM("G33 Auto Calibrate");
168 184
 
169 185
   stepper.synchronize();
186
+
170 187
   #if HAS_LEVELING
171 188
     reset_bed_level(); // After calibration bed-level data is no longer valid
172 189
   #endif
@@ -274,7 +291,7 @@ void gcode_G33() {
274 291
 
275 292
     if ((zero_std_dev < test_precision && zero_std_dev > calibration_precision) || iterations <= force_iterations) {
276 293
       if (zero_std_dev < zero_std_dev_min) {
277
-        COPY(e_old, endstop_adj);
294
+        COPY(e_old, delta_endstop_adj);
278 295
         dr_old = delta_radius;
279 296
         zh_old = home_offset[Z_AXIS];
280 297
         alpha_old = delta_tower_angle_trim[A_AXIS];
@@ -337,20 +354,20 @@ void gcode_G33() {
337 354
           break;
338 355
       }
339 356
 
340
-      LOOP_XYZ(axis) endstop_adj[axis] += e_delta[axis];
357
+      LOOP_XYZ(axis) delta_endstop_adj[axis] += e_delta[axis];
341 358
       delta_radius += r_delta;
342 359
       delta_tower_angle_trim[A_AXIS] += t_alpha;
343 360
       delta_tower_angle_trim[B_AXIS] += t_beta;
344 361
 
345 362
       // adjust delta_height and endstops by the max amount
346
-      const float z_temp = MAX3(endstop_adj[A_AXIS], endstop_adj[B_AXIS], endstop_adj[C_AXIS]);
363
+      const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
347 364
       home_offset[Z_AXIS] -= z_temp;
348
-      LOOP_XYZ(i) endstop_adj[i] -= z_temp;
365
+      LOOP_XYZ(i) delta_endstop_adj[i] -= z_temp;
349 366
 
350 367
       recalc_delta_settings(delta_radius, delta_diagonal_rod);
351 368
     }
352 369
     else if (zero_std_dev >= test_precision) {   // step one back
353
-      COPY(endstop_adj, e_old);
370
+      COPY(delta_endstop_adj, e_old);
354 371
       delta_radius = dr_old;
355 372
       home_offset[Z_AXIS] = zh_old;
356 373
       delta_tower_angle_trim[A_AXIS] = alpha_old;
@@ -449,3 +466,5 @@ void gcode_G33() {
449 466
 
450 467
   G33_CLEANUP();
451 468
 }
469
+
470
+#endif // DELTA_AUTO_CALIBRATION

+ 5
- 5
Marlin/src/gcode/calibrate/M666.h View File

@@ -33,11 +33,11 @@
33 33
     #endif
34 34
     LOOP_XYZ(i) {
35 35
       if (parser.seen(axis_codes[i])) {
36
-        endstop_adj[i] = parser.value_linear_units();
36
+        delta_endstop_adj[i] = parser.value_linear_units();
37 37
         #if ENABLED(DEBUG_LEVELING_FEATURE)
38 38
           if (DEBUGGING(LEVELING)) {
39
-            SERIAL_ECHOPAIR("endstop_adj[", axis_codes[i]);
40
-            SERIAL_ECHOLNPAIR("] = ", endstop_adj[i]);
39
+            SERIAL_ECHOPAIR("delta_endstop_adj[", axis_codes[i]);
40
+            SERIAL_ECHOLNPAIR("] = ", delta_endstop_adj[i]);
41 41
           }
42 42
         #endif
43 43
       }
@@ -48,9 +48,9 @@
48 48
       }
49 49
     #endif
50 50
     // normalize endstops so all are <=0; set the residue to delta height
51
-    const float z_temp = MAX3(endstop_adj[A_AXIS], endstop_adj[B_AXIS], endstop_adj[C_AXIS]);
51
+    const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
52 52
     home_offset[Z_AXIS] -= z_temp;
53
-    LOOP_XYZ(i) endstop_adj[i] -= z_temp;
53
+    LOOP_XYZ(i) delta_endstop_adj[i] -= z_temp;
54 54
   }
55 55
 
56 56
 #elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS)

+ 0
- 81
Marlin/src/gcode/calibrate/common.h View File

@@ -1,81 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#ifndef CALIBRATE_COMMON_H
24
-#define CALIBRATE_COMMON_H
25
-
26
-#if ENABLED(DELTA)
27
-
28
-  /**
29
-   * A delta can only safely home all axes at the same time
30
-   * This is like quick_home_xy() but for 3 towers.
31
-   */
32
-  inline bool home_delta() {
33
-    #if ENABLED(DEBUG_LEVELING_FEATURE)
34
-      if (DEBUGGING(LEVELING)) DEBUG_POS(">>> home_delta", current_position);
35
-    #endif
36
-    // Init the current position of all carriages to 0,0,0
37
-    ZERO(current_position);
38
-    sync_plan_position();
39
-
40
-    // Move all carriages together linearly until an endstop is hit.
41
-    current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (DELTA_HEIGHT + home_offset[Z_AXIS] + 10);
42
-    feedrate_mm_s = homing_feedrate(X_AXIS);
43
-    line_to_current_position();
44
-    stepper.synchronize();
45
-
46
-    // If an endstop was not hit, then damage can occur if homing is continued.
47
-    // This can occur if the delta height (DELTA_HEIGHT + home_offset[Z_AXIS]) is
48
-    // not set correctly.
49
-    if (!(Endstops::endstop_hit_bits & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)))) {
50
-      LCD_MESSAGEPGM(MSG_ERR_HOMING_FAILED);
51
-      SERIAL_ERROR_START();
52
-      SERIAL_ERRORLNPGM(MSG_ERR_HOMING_FAILED);
53
-      return false;
54
-    }
55
-
56
-    endstops.hit_on_purpose(); // clear endstop hit flags
57
-
58
-    // At least one carriage has reached the top.
59
-    // Now re-home each carriage separately.
60
-    HOMEAXIS(A);
61
-    HOMEAXIS(B);
62
-    HOMEAXIS(C);
63
-
64
-    // Set all carriages to their home positions
65
-    // Do this here all at once for Delta, because
66
-    // XYZ isn't ABC. Applying this per-tower would
67
-    // give the impression that they are the same.
68
-    LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i);
69
-
70
-    SYNC_PLAN_POSITION_KINEMATIC();
71
-
72
-    #if ENABLED(DEBUG_LEVELING_FEATURE)
73
-      if (DEBUGGING(LEVELING)) DEBUG_POS("<<< home_delta", current_position);
74
-    #endif
75
-
76
-    return true;
77
-  }
78
-
79
-#endif // DELTA
80
-
81
-#endif // CALIBRATE_COMMON_H

+ 1
- 1
Marlin/src/gcode/control/M18_M84.h View File

@@ -47,7 +47,7 @@ void gcode_M18_M84() {
47 47
     }
48 48
 
49 49
     #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD)  // Only needed with an LCD
50
-      ubl_lcd_map_control = defer_return_to_status = false;
50
+      ubl.lcd_map_control = defer_return_to_status = false;
51 51
     #endif
52 52
   }
53 53
 }

+ 16
- 32
Marlin/src/gcode/gcode.cpp View File

@@ -115,14 +115,10 @@ extern void gcode_G18();
115 115
 extern void gcode_G19();
116 116
 extern void gcode_G20();
117 117
 extern void gcode_G21();
118
-extern void gcode_G26();
119 118
 extern void gcode_G27();
120
-extern void gcode_G28(const bool always_home_all);
121
-extern void gcode_G29();
122 119
 extern void gcode_G30();
123 120
 extern void gcode_G31();
124 121
 extern void gcode_G32();
125
-extern void gcode_G33();
126 122
 extern void gcode_G38(bool is_38_2);
127 123
 extern void gcode_G42();
128 124
 extern void gcode_G92();
@@ -149,7 +145,6 @@ extern void gcode_M34();
149 145
 extern void gcode_M42();
150 146
 extern void gcode_M43();
151 147
 extern void gcode_M48();
152
-extern void gcode_M49();
153 148
 extern void gcode_M75();
154 149
 extern void gcode_M76();
155 150
 extern void gcode_M77();
@@ -225,8 +220,6 @@ extern void gcode_M405();
225 220
 extern void gcode_M406();
226 221
 extern void gcode_M407();
227 222
 extern void gcode_M410();
228
-extern void gcode_M420();
229
-extern void gcode_M421();
230 223
 extern void gcode_M428();
231 224
 extern void gcode_M500();
232 225
 extern void gcode_M501();
@@ -238,7 +231,6 @@ extern void gcode_M605();
238 231
 extern void gcode_M665();
239 232
 extern void gcode_M666();
240 233
 extern void gcode_M702();
241
-extern void gcode_M851();
242 234
 extern void gcode_M900();
243 235
 extern void gcode_M906();
244 236
 extern void gcode_M911();
@@ -348,9 +340,9 @@ void GcodeSuite::process_next_command() {
348 340
           break;
349 341
       #endif // INCH_MODE_SUPPORT
350 342
 
351
-      #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION)
343
+      #if ENABLED(UBL_G26_MESH_VALIDATION)
352 344
         case 26: // G26: Mesh Validation Pattern generation
353
-          gcode_G26();
345
+          G26();
354 346
           break;
355 347
       #endif // AUTO_BED_LEVELING_UBL
356 348
 
@@ -361,13 +353,13 @@ void GcodeSuite::process_next_command() {
361 353
       #endif // NOZZLE_PARK_FEATURE
362 354
 
363 355
       case 28: // G28: Home all axes, one at a time
364
-        gcode_G28(false);
356
+        G28(false);
365 357
         break;
366 358
 
367 359
       #if HAS_LEVELING
368 360
         case 29: // G29 Detailed Z probe, probes the bed at 3 or more points,
369 361
                  // or provides access to the UBL System if enabled.
370
-          gcode_G29();
362
+          G29();
371 363
           break;
372 364
       #endif // HAS_LEVELING
373 365
 
@@ -391,17 +383,11 @@ void GcodeSuite::process_next_command() {
391 383
 
392 384
       #endif // HAS_BED_PROBE
393 385
 
394
-      #if PROBE_SELECTED
395
-
396
-        #if ENABLED(DELTA_AUTO_CALIBRATION)
397
-
398
-          case 33: // G33: Delta Auto-Calibration
399
-            gcode_G33();
400
-            break;
401
-
402
-        #endif // DELTA_AUTO_CALIBRATION
403
-
404
-      #endif // PROBE_SELECTED
386
+      #if ENABLED(DELTA_AUTO_CALIBRATION)
387
+        case 33: // G33: Delta Auto-Calibration
388
+          G33();
389
+          break;
390
+      #endif // DELTA_AUTO_CALIBRATION
405 391
 
406 392
       #if ENABLED(G38_PROBE_TARGET)
407 393
         case 38: // G38.2 & G38.3
@@ -516,11 +502,9 @@ void GcodeSuite::process_next_command() {
516 502
           break;
517 503
       #endif // Z_MIN_PROBE_REPEATABILITY_TEST
518 504
 
519
-      #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION)
520
-        case 49: // M49: Turn on or off G26 debug flag for verbose output
521
-          gcode_M49();
522
-          break;
523
-      #endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_VALIDATION
505
+      #if ENABLED(UBL_G26_MESH_VALIDATION)
506
+        case 49: M49(); break;    // M49: Turn on or off G26 debug flag for verbose output
507
+      #endif
524 508
 
525 509
       case 75: // M75: Start print timer
526 510
         gcode_M75(); break;
@@ -901,13 +885,13 @@ void GcodeSuite::process_next_command() {
901 885
 
902 886
       #if HAS_LEVELING
903 887
         case 420: // M420: Enable/Disable Bed Leveling
904
-          gcode_M420();
888
+          M420();
905 889
           break;
906 890
       #endif
907 891
 
908
-      #if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
892
+      #if HAS_MESH
909 893
         case 421: // M421: Set a Mesh Bed Leveling Z coordinate
910
-          gcode_M421();
894
+          M421();
911 895
           break;
912 896
       #endif
913 897
 
@@ -941,7 +925,7 @@ void GcodeSuite::process_next_command() {
941 925
 
942 926
       #if HAS_BED_PROBE
943 927
         case 851: // M851: Set Z Probe Z Offset
944
-          gcode_M851();
928
+          M851();
945 929
           break;
946 930
       #endif // HAS_BED_PROBE
947 931
 

Marlin/src/gcode/probe/M851.h → Marlin/src/gcode/probe/M851.cpp View File

@@ -20,43 +20,15 @@
20 20
  *
21 21
  */
22 22
 
23
-void refresh_zprobe_zoffset(const bool no_babystep/*=false*/) {
24
-  static float last_zoffset = NAN;
23
+#include "../../inc/MarlinConfig.h"
25 24
 
26
-  if (!isnan(last_zoffset)) {
25
+#if HAS_BED_PROBE
27 26
 
28
-    #if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(BABYSTEP_ZPROBE_OFFSET) || ENABLED(DELTA)
29
-      const float diff = zprobe_zoffset - last_zoffset;
30
-    #endif
27
+#include "../gcode.h"
28
+#include "../../feature/bedlevel/bedlevel.h"
29
+#include "../../module/probe.h"
31 30
 
32
-    #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
33
-      // Correct bilinear grid for new probe offset
34
-      if (diff) {
35
-        for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
36
-          for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
37
-            z_values[x][y] -= diff;
38
-      }
39
-      #if ENABLED(ABL_BILINEAR_SUBDIVISION)
40
-        bed_level_virt_interpolate();
41
-      #endif
42
-    #endif
43
-
44
-    #if ENABLED(BABYSTEP_ZPROBE_OFFSET)
45
-      if (!no_babystep && leveling_is_active())
46
-        thermalManager.babystep_axis(Z_AXIS, -LROUND(diff * planner.axis_steps_per_mm[Z_AXIS]));
47
-    #else
48
-      UNUSED(no_babystep);
49
-    #endif
50
-
51
-    #if ENABLED(DELTA) // correct the delta_height
52
-      home_offset[Z_AXIS] -= diff;
53
-    #endif
54
-  }
55
-
56
-  last_zoffset = zprobe_zoffset;
57
-}
58
-
59
-void gcode_M851() {
31
+void GcodeSuite::M851() {
60 32
   SERIAL_ECHO_START();
61 33
   SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET " ");
62 34
   if (parser.seen('Z')) {
@@ -74,3 +46,5 @@ void gcode_M851() {
74 46
 
75 47
   SERIAL_EOL();
76 48
 }
49
+
50
+#endif // HAS_BED_PROBE

+ 6
- 5
Marlin/src/lcd/ultralcd.cpp View File

@@ -31,6 +31,7 @@
31 31
 #include "../module/planner.h"
32 32
 #include "../module/stepper.h"
33 33
 #include "../module/motion.h"
34
+#include "../module/probe.h"
34 35
 #include "../gcode/gcode.h"
35 36
 #include "../gcode/queue.h"
36 37
 #include "../module/configuration_store.h"
@@ -173,7 +174,7 @@ uint16_t max_display_update_time = 0;
173 174
   #endif
174 175
 
175 176
   #if ENABLED(MESH_BED_LEVELING) && ENABLED(LCD_BED_LEVELING)
176
-    #include "../feature/mbl/mesh_bed_leveling.h"
177
+    #include "../feature/bedlevel/mbl/mesh_bed_leveling.h"
177 178
     extern void mesh_probing_done();
178 179
   #endif
179 180
 
@@ -1021,7 +1022,7 @@ void kill_screen(const char* lcd_msg) {
1021 1022
           const float new_zoffset = zprobe_zoffset + planner.steps_to_mm[Z_AXIS] * babystep_increment;
1022 1023
           if (WITHIN(new_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) {
1023 1024
 
1024
-            if (planner.abl_enabled)
1025
+            if (leveling_is_active())
1025 1026
               thermalManager.babystep_axis(Z_AXIS, babystep_increment);
1026 1027
 
1027 1028
             zprobe_zoffset = new_zoffset;
@@ -2635,9 +2636,9 @@ void kill_screen(const char* lcd_msg) {
2635 2636
       MENU_ITEM_EDIT(float52, MSG_DELTA_DIAG_ROG, &delta_diagonal_rod, DELTA_DIAGONAL_ROD - 5.0, DELTA_DIAGONAL_ROD + 5.0);
2636 2637
       _delta_height = DELTA_HEIGHT + home_offset[Z_AXIS];
2637 2638
       MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_DELTA_HEIGHT, &_delta_height, _delta_height - 10.0, _delta_height + 10.0, _lcd_set_delta_height);
2638
-      MENU_ITEM_EDIT(float43, "Ex", &endstop_adj[A_AXIS], -5.0, 5.0);
2639
-      MENU_ITEM_EDIT(float43, "Ey", &endstop_adj[B_AXIS], -5.0, 5.0);
2640
-      MENU_ITEM_EDIT(float43, "Ez", &endstop_adj[C_AXIS], -5.0, 5.0);
2639
+      MENU_ITEM_EDIT(float43, "Ex", &delta_endstop_adj[A_AXIS], -5.0, 5.0);
2640
+      MENU_ITEM_EDIT(float43, "Ey", &delta_endstop_adj[B_AXIS], -5.0, 5.0);
2641
+      MENU_ITEM_EDIT(float43, "Ez", &delta_endstop_adj[C_AXIS], -5.0, 5.0);
2641 2642
       MENU_ITEM_EDIT(float52, MSG_DELTA_RADIUS, &delta_radius, DELTA_RADIUS - 5.0, DELTA_RADIUS + 5.0);
2642 2643
       MENU_ITEM_EDIT(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5.0, 5.0);
2643 2644
       MENU_ITEM_EDIT(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5.0, 5.0);

+ 1
- 1
Marlin/src/lcd/ultralcd_impl_DOGM.h View File

@@ -52,7 +52,7 @@
52 52
 #include <U8glib.h>
53 53
 
54 54
 #if ENABLED(AUTO_BED_LEVELING_UBL)
55
-  #include "../feature/ubl/ubl.h"
55
+  #include "../feature/bedlevel/ubl/ubl.h"
56 56
 #endif
57 57
 
58 58
 #if ENABLED(SHOW_BOOTSCREEN) && ENABLED(SHOW_CUSTOM_BOOTSCREEN)

+ 1
- 1
Marlin/src/lcd/ultralcd_impl_HD44780.h View File

@@ -35,7 +35,7 @@
35 35
 #endif
36 36
 
37 37
 #if ENABLED(AUTO_BED_LEVELING_UBL)
38
-  #include "../feature/ubl/ubl.h"
38
+  #include "../feature/bedlevel/ubl/ubl.h"
39 39
 
40 40
   #if ENABLED(ULTIPANEL)
41 41
     #define ULTRA_X_PIXELS_PER_CHAR    5

+ 11
- 15
Marlin/src/module/configuration_store.cpp View File

@@ -93,7 +93,7 @@
93 93
  *  329  G29 S     ubl.state.storage_slot           (int8_t)
94 94
  *
95 95
  * DELTA:                                           48 bytes
96
- *  348  M666 XYZ  endstop_adj                      (float x3)
96
+ *  348  M666 XYZ  delta_endstop_adj                      (float x3)
97 97
  *  360  M665 R    delta_radius                     (float)
98 98
  *  364  M665 L    delta_diagonal_rod               (float)
99 99
  *  368  M665 S    delta_segments_per_second        (float)
@@ -187,6 +187,10 @@ MarlinSettings settings;
187 187
 
188 188
 #include "../gcode/parser.h"
189 189
 
190
+#if HAS_LEVELING
191
+  #include "../feature/bedlevel/bedlevel.h"
192
+#endif
193
+
190 194
 #if HAS_BED_PROBE
191 195
   #include "../module/probe.h"
192 196
 #endif
@@ -199,14 +203,6 @@ MarlinSettings settings;
199 203
   #include "../feature/fwretract.h"
200 204
 #endif
201 205
 
202
-#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
203
-  extern void refresh_bed_level();
204
-#endif
205
-
206
-#if ENABLED(FWRETRACT)
207
-  #include "../gcode/feature/fwretract/fwretract.h"
208
-#endif
209
-
210 206
 /**
211 207
  * Post-process after Retrieve or Reset
212 208
  */
@@ -421,7 +417,7 @@ void MarlinSettings::postprocess() {
421 417
 
422 418
     // 9 floats for DELTA / Z_DUAL_ENDSTOPS
423 419
     #if ENABLED(DELTA)
424
-      EEPROM_WRITE(endstop_adj);               // 3 floats
420
+      EEPROM_WRITE(delta_endstop_adj);               // 3 floats
425 421
       EEPROM_WRITE(delta_radius);              // 1 float
426 422
       EEPROM_WRITE(delta_diagonal_rod);        // 1 float
427 423
       EEPROM_WRITE(delta_segments_per_second); // 1 float
@@ -806,7 +802,7 @@ void MarlinSettings::postprocess() {
806 802
       #endif // AUTO_BED_LEVELING_UBL
807 803
 
808 804
       #if ENABLED(DELTA)
809
-        EEPROM_READ(endstop_adj);               // 3 floats
805
+        EEPROM_READ(delta_endstop_adj);               // 3 floats
810 806
         EEPROM_READ(delta_radius);              // 1 float
811 807
         EEPROM_READ(delta_diagonal_rod);        // 1 float
812 808
         EEPROM_READ(delta_segments_per_second); // 1 float
@@ -1196,7 +1192,7 @@ void MarlinSettings::reset() {
1196 1192
   #if ENABLED(DELTA)
1197 1193
     const float adj[ABC] = DELTA_ENDSTOP_ADJ,
1198 1194
                 dta[ABC] = DELTA_TOWER_ANGLE_TRIM;
1199
-    COPY(endstop_adj, adj);
1195
+    COPY(delta_endstop_adj, adj);
1200 1196
     delta_radius = DELTA_RADIUS;
1201 1197
     delta_diagonal_rod = DELTA_DIAGONAL_ROD;
1202 1198
     delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
@@ -1602,9 +1598,9 @@ void MarlinSettings::reset() {
1602 1598
         SERIAL_ECHOLNPGM("Endstop adjustment:");
1603 1599
       }
1604 1600
       CONFIG_ECHO_START;
1605
-      SERIAL_ECHOPAIR("  M666 X", LINEAR_UNIT(endstop_adj[X_AXIS]));
1606
-      SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(endstop_adj[Y_AXIS]));
1607
-      SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(endstop_adj[Z_AXIS]));
1601
+      SERIAL_ECHOPAIR("  M666 X", LINEAR_UNIT(delta_endstop_adj[X_AXIS]));
1602
+      SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(delta_endstop_adj[Y_AXIS]));
1603
+      SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(delta_endstop_adj[Z_AXIS]));
1608 1604
       if (!forReplay) {
1609 1605
         CONFIG_ECHO_START;
1610 1606
         SERIAL_ECHOLNPGM("Delta settings: L<diagonal_rod> R<radius> H<height> S<segments_per_s> B<calibration radius> XYZ<tower angle corrections>");

+ 269
- 0
Marlin/src/module/delta.cpp View File

@@ -0,0 +1,269 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * delta.cpp
25
+ */
26
+
27
+#include "../inc/MarlinConfig.h"
28
+
29
+#if ENABLED(DELTA)
30
+
31
+#include "delta.h"
32
+#include "motion.h"
33
+
34
+// For homing:
35
+#include "stepper.h"
36
+#include "endstops.h"
37
+#include "../lcd/ultralcd.h"
38
+#include "../Marlin.h"
39
+
40
+// Initialized by settings.load()
41
+float delta_endstop_adj[ABC] = { 0 },
42
+      delta_radius,
43
+      delta_diagonal_rod,
44
+      delta_segments_per_second,
45
+      delta_calibration_radius,
46
+      delta_tower_angle_trim[2];
47
+
48
+float delta_tower[ABC][2],
49
+      delta_diagonal_rod_2_tower[ABC],
50
+      delta_clip_start_height = Z_MAX_POS;
51
+
52
+float delta_safe_distance_from_top();
53
+
54
+/**
55
+ * Recalculate factors used for delta kinematics whenever
56
+ * settings have been changed (e.g., by M665).
57
+ */
58
+void recalc_delta_settings(float radius, float diagonal_rod) {
59
+  const float trt[ABC] = DELTA_RADIUS_TRIM_TOWER,
60
+              drt[ABC] = DELTA_DIAGONAL_ROD_TRIM_TOWER;
61
+  delta_tower[A_AXIS][X_AXIS] = cos(RADIANS(210 + delta_tower_angle_trim[A_AXIS])) * (radius + trt[A_AXIS]); // front left tower
62
+  delta_tower[A_AXIS][Y_AXIS] = sin(RADIANS(210 + delta_tower_angle_trim[A_AXIS])) * (radius + trt[A_AXIS]);
63
+  delta_tower[B_AXIS][X_AXIS] = cos(RADIANS(330 + delta_tower_angle_trim[B_AXIS])) * (radius + trt[B_AXIS]); // front right tower
64
+  delta_tower[B_AXIS][Y_AXIS] = sin(RADIANS(330 + delta_tower_angle_trim[B_AXIS])) * (radius + trt[B_AXIS]);
65
+  delta_tower[C_AXIS][X_AXIS] = 0.0; // back middle tower
66
+  delta_tower[C_AXIS][Y_AXIS] = (radius + trt[C_AXIS]);
67
+  delta_diagonal_rod_2_tower[A_AXIS] = sq(diagonal_rod + drt[A_AXIS]);
68
+  delta_diagonal_rod_2_tower[B_AXIS] = sq(diagonal_rod + drt[B_AXIS]);
69
+  delta_diagonal_rod_2_tower[C_AXIS] = sq(diagonal_rod + drt[C_AXIS]);
70
+}
71
+
72
+/**
73
+ * Delta Inverse Kinematics
74
+ *
75
+ * Calculate the tower positions for a given logical
76
+ * position, storing the result in the delta[] array.
77
+ *
78
+ * This is an expensive calculation, requiring 3 square
79
+ * roots per segmented linear move, and strains the limits
80
+ * of a Mega2560 with a Graphical Display.
81
+ *
82
+ * Suggested optimizations include:
83
+ *
84
+ * - Disable the home_offset (M206) and/or position_shift (G92)
85
+ *   features to remove up to 12 float additions.
86
+ *
87
+ * - Use a fast-inverse-sqrt function and add the reciprocal.
88
+ *   (see above)
89
+ */
90
+
91
+#if ENABLED(DELTA_FAST_SQRT) && defined(ARDUINO_ARCH_AVR)
92
+  /**
93
+   * Fast inverse sqrt from Quake III Arena
94
+   * See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
95
+   */
96
+  float Q_rsqrt(float number) {
97
+    long i;
98
+    float x2, y;
99
+    const float threehalfs = 1.5f;
100
+    x2 = number * 0.5f;
101
+    y  = number;
102
+    i  = * ( long * ) &y;                       // evil floating point bit level hacking
103
+    i  = 0x5F3759DF - ( i >> 1 );               // what the f***?
104
+    y  = * ( float * ) &i;
105
+    y  = y * ( threehalfs - ( x2 * y * y ) );   // 1st iteration
106
+    // y  = y * ( threehalfs - ( x2 * y * y ) );   // 2nd iteration, this can be removed
107
+    return y;
108
+  }
109
+#endif
110
+
111
+#define DELTA_DEBUG() do { \
112
+    SERIAL_ECHOPAIR("cartesian X:", raw[X_AXIS]); \
113
+    SERIAL_ECHOPAIR(" Y:", raw[Y_AXIS]);          \
114
+    SERIAL_ECHOLNPAIR(" Z:", raw[Z_AXIS]);        \
115
+    SERIAL_ECHOPAIR("delta A:", delta[A_AXIS]);   \
116
+    SERIAL_ECHOPAIR(" B:", delta[B_AXIS]);        \
117
+    SERIAL_ECHOLNPAIR(" C:", delta[C_AXIS]);      \
118
+  }while(0)
119
+
120
+void inverse_kinematics(const float logical[XYZ]) {
121
+  DELTA_LOGICAL_IK();
122
+  // DELTA_DEBUG();
123
+}
124
+
125
+/**
126
+ * Calculate the highest Z position where the
127
+ * effector has the full range of XY motion.
128
+ */
129
+float delta_safe_distance_from_top() {
130
+  float cartesian[XYZ] = {
131
+    LOGICAL_X_POSITION(0),
132
+    LOGICAL_Y_POSITION(0),
133
+    LOGICAL_Z_POSITION(0)
134
+  };
135
+  inverse_kinematics(cartesian);
136
+  float distance = delta[A_AXIS];
137
+  cartesian[Y_AXIS] = LOGICAL_Y_POSITION(DELTA_PRINTABLE_RADIUS);
138
+  inverse_kinematics(cartesian);
139
+  return FABS(distance - delta[A_AXIS]);
140
+}
141
+
142
+/**
143
+ * Delta Forward Kinematics
144
+ *
145
+ * See the Wikipedia article "Trilateration"
146
+ * https://en.wikipedia.org/wiki/Trilateration
147
+ *
148
+ * Establish a new coordinate system in the plane of the
149
+ * three carriage points. This system has its origin at
150
+ * tower1, with tower2 on the X axis. Tower3 is in the X-Y
151
+ * plane with a Z component of zero.
152
+ * We will define unit vectors in this coordinate system
153
+ * in our original coordinate system. Then when we calculate
154
+ * the Xnew, Ynew and Znew values, we can translate back into
155
+ * the original system by moving along those unit vectors
156
+ * by the corresponding values.
157
+ *
158
+ * Variable names matched to Marlin, c-version, and avoid the
159
+ * use of any vector library.
160
+ *
161
+ * by Andreas Hardtung 2016-06-07
162
+ * based on a Java function from "Delta Robot Kinematics V3"
163
+ * by Steve Graves
164
+ *
165
+ * The result is stored in the cartes[] array.
166
+ */
167
+void forward_kinematics_DELTA(float z1, float z2, float z3) {
168
+  // Create a vector in old coordinates along x axis of new coordinate
169
+  float p12[3] = { delta_tower[B_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[B_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z2 - z1 };
170
+
171
+  // Get the Magnitude of vector.
172
+  float d = SQRT( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) );
173
+
174
+  // Create unit vector by dividing by magnitude.
175
+  float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d };
176
+
177
+  // Get the vector from the origin of the new system to the third point.
178
+  float p13[3] = { delta_tower[C_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[C_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z3 - z1 };
179
+
180
+  // Use the dot product to find the component of this vector on the X axis.
181
+  float i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2];
182
+
183
+  // Create a vector along the x axis that represents the x component of p13.
184
+  float iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i };
185
+
186
+  // Subtract the X component from the original vector leaving only Y. We use the
187
+  // variable that will be the unit vector after we scale it.
188
+  float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
189
+
190
+  // The magnitude of Y component
191
+  float j = SQRT( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) );
192
+
193
+  // Convert to a unit vector
194
+  ey[0] /= j; ey[1] /= j;  ey[2] /= j;
195
+
196
+  // The cross product of the unit x and y is the unit z
197
+  // float[] ez = vectorCrossProd(ex, ey);
198
+  float ez[3] = {
199
+    ex[1] * ey[2] - ex[2] * ey[1],
200
+    ex[2] * ey[0] - ex[0] * ey[2],
201
+    ex[0] * ey[1] - ex[1] * ey[0]
202
+  };
203
+
204
+  // We now have the d, i and j values defined in Wikipedia.
205
+  // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
206
+  float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + sq(d)) / (d * 2),
207
+        Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + HYPOT2(i, j)) / 2 - i * Xnew) / j,
208
+        Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew));
209
+
210
+  // Start from the origin of the old coordinates and add vectors in the
211
+  // old coords that represent the Xnew, Ynew and Znew to find the point
212
+  // in the old system.
213
+  cartes[X_AXIS] = delta_tower[A_AXIS][X_AXIS] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew;
214
+  cartes[Y_AXIS] = delta_tower[A_AXIS][Y_AXIS] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew;
215
+  cartes[Z_AXIS] =             z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew;
216
+}
217
+
218
+/**
219
+ * A delta can only safely home all axes at the same time
220
+ * This is like quick_home_xy() but for 3 towers.
221
+ */
222
+bool home_delta() {
223
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
224
+    if (DEBUGGING(LEVELING)) DEBUG_POS(">>> home_delta", current_position);
225
+  #endif
226
+  // Init the current position of all carriages to 0,0,0
227
+  ZERO(current_position);
228
+  sync_plan_position();
229
+
230
+  // Move all carriages together linearly until an endstop is hit.
231
+  current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (DELTA_HEIGHT + home_offset[Z_AXIS] + 10);
232
+  feedrate_mm_s = homing_feedrate(X_AXIS);
233
+  line_to_current_position();
234
+  stepper.synchronize();
235
+
236
+  // If an endstop was not hit, then damage can occur if homing is continued.
237
+  // This can occur if the delta height (DELTA_HEIGHT + home_offset[Z_AXIS]) is
238
+  // not set correctly.
239
+  if (!(Endstops::endstop_hit_bits & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)))) {
240
+    LCD_MESSAGEPGM(MSG_ERR_HOMING_FAILED);
241
+    SERIAL_ERROR_START();
242
+    SERIAL_ERRORLNPGM(MSG_ERR_HOMING_FAILED);
243
+    return false;
244
+  }
245
+
246
+  endstops.hit_on_purpose(); // clear endstop hit flags
247
+
248
+  // At least one carriage has reached the top.
249
+  // Now re-home each carriage separately.
250
+  HOMEAXIS(A);
251
+  HOMEAXIS(B);
252
+  HOMEAXIS(C);
253
+
254
+  // Set all carriages to their home positions
255
+  // Do this here all at once for Delta, because
256
+  // XYZ isn't ABC. Applying this per-tower would
257
+  // give the impression that they are the same.
258
+  LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i);
259
+
260
+  SYNC_PLAN_POSITION_KINEMATIC();
261
+
262
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
263
+    if (DEBUGGING(LEVELING)) DEBUG_POS("<<< home_delta", current_position);
264
+  #endif
265
+
266
+  return true;
267
+}
268
+
269
+#endif // DELTA

+ 141
- 0
Marlin/src/module/delta.h View File

@@ -0,0 +1,141 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * delta.h - Delta-specific functions
25
+ */
26
+
27
+#ifndef __DELTA_H__
28
+#define __DELTA_H__
29
+
30
+extern float delta_endstop_adj[ABC],
31
+             delta_radius,
32
+             delta_diagonal_rod,
33
+             delta_segments_per_second,
34
+             delta_calibration_radius,
35
+             delta_tower_angle_trim[2];
36
+
37
+extern float delta_tower[ABC][2],
38
+             delta_diagonal_rod_2_tower[ABC],
39
+             delta_clip_start_height;
40
+
41
+/**
42
+ * Recalculate factors used for delta kinematics whenever
43
+ * settings have been changed (e.g., by M665).
44
+ */
45
+void recalc_delta_settings(float radius, float diagonal_rod);
46
+
47
+/**
48
+ * Delta Inverse Kinematics
49
+ *
50
+ * Calculate the tower positions for a given logical
51
+ * position, storing the result in the delta[] array.
52
+ *
53
+ * This is an expensive calculation, requiring 3 square
54
+ * roots per segmented linear move, and strains the limits
55
+ * of a Mega2560 with a Graphical Display.
56
+ *
57
+ * Suggested optimizations include:
58
+ *
59
+ * - Disable the home_offset (M206) and/or position_shift (G92)
60
+ *   features to remove up to 12 float additions.
61
+ *
62
+ * - Use a fast-inverse-sqrt function and add the reciprocal.
63
+ *   (see above)
64
+ */
65
+
66
+#if ENABLED(DELTA_FAST_SQRT) && defined(ARDUINO_ARCH_AVR)
67
+  /**
68
+   * Fast inverse sqrt from Quake III Arena
69
+   * See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
70
+   */
71
+  float Q_rsqrt(float number);
72
+  #define _SQRT(n) (1.0f / Q_rsqrt(n))
73
+#else
74
+  #define _SQRT(n) SQRT(n)
75
+#endif
76
+
77
+// Macro to obtain the Z position of an individual tower
78
+#define DELTA_Z(T) raw[Z_AXIS] + _SQRT(     \
79
+  delta_diagonal_rod_2_tower[T] - HYPOT2(   \
80
+      delta_tower[T][X_AXIS] - raw[X_AXIS], \
81
+      delta_tower[T][Y_AXIS] - raw[Y_AXIS]  \
82
+    )                                       \
83
+  )
84
+
85
+#define DELTA_RAW_IK() do {        \
86
+  delta[A_AXIS] = DELTA_Z(A_AXIS); \
87
+  delta[B_AXIS] = DELTA_Z(B_AXIS); \
88
+  delta[C_AXIS] = DELTA_Z(C_AXIS); \
89
+}while(0)
90
+
91
+#define DELTA_LOGICAL_IK() do {      \
92
+  const float raw[XYZ] = {           \
93
+    RAW_X_POSITION(logical[X_AXIS]), \
94
+    RAW_Y_POSITION(logical[Y_AXIS]), \
95
+    RAW_Z_POSITION(logical[Z_AXIS])  \
96
+  };                                 \
97
+  DELTA_RAW_IK();                    \
98
+}while(0)
99
+
100
+void inverse_kinematics(const float logical[XYZ]);
101
+
102
+/**
103
+ * Calculate the highest Z position where the
104
+ * effector has the full range of XY motion.
105
+ */
106
+float delta_safe_distance_from_top();
107
+
108
+/**
109
+ * Delta Forward Kinematics
110
+ *
111
+ * See the Wikipedia article "Trilateration"
112
+ * https://en.wikipedia.org/wiki/Trilateration
113
+ *
114
+ * Establish a new coordinate system in the plane of the
115
+ * three carriage points. This system has its origin at
116
+ * tower1, with tower2 on the X axis. Tower3 is in the X-Y
117
+ * plane with a Z component of zero.
118
+ * We will define unit vectors in this coordinate system
119
+ * in our original coordinate system. Then when we calculate
120
+ * the Xnew, Ynew and Znew values, we can translate back into
121
+ * the original system by moving along those unit vectors
122
+ * by the corresponding values.
123
+ *
124
+ * Variable names matched to Marlin, c-version, and avoid the
125
+ * use of any vector library.
126
+ *
127
+ * by Andreas Hardtung 2016-06-07
128
+ * based on a Java function from "Delta Robot Kinematics V3"
129
+ * by Steve Graves
130
+ *
131
+ * The result is stored in the cartes[] array.
132
+ */
133
+void forward_kinematics_DELTA(float z1, float z2, float z3);
134
+
135
+FORCE_INLINE void forward_kinematics_DELTA(float point[ABC]) {
136
+  forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]);
137
+}
138
+
139
+bool home_delta();
140
+
141
+#endif // __DELTA_H__

+ 770
- 73
Marlin/src/module/motion.cpp View File

@@ -25,23 +25,38 @@
25 25
  */
26 26
 
27 27
 #include "motion.h"
28
+#include "endstops.h"
29
+#include "stepper.h"
30
+#include "planner.h"
31
+#include "temperature.h"
28 32
 
29 33
 #include "../gcode/gcode.h"
30
-// #include "../module/planner.h"
31
-// #include "../Marlin.h"
32
-// #include "../inc/MarlinConfig.h"
33 34
 
34
-#include "../core/serial.h"
35
-#include "../module/stepper.h"
36
-#include "../module/temperature.h"
35
+#include "../inc/MarlinConfig.h"
37 36
 
38 37
 #if IS_SCARA
39 38
   #include "../libs/buzzer.h"
40 39
   #include "../lcd/ultralcd.h"
41 40
 #endif
42 41
 
43
-#if ENABLED(AUTO_BED_LEVELING_UBL)
44
-  #include "../feature/ubl/ubl.h"
42
+// #if ENABLED(DUAL_X_CARRIAGE)
43
+//   #include "tool_change.h"
44
+// #endif
45
+
46
+#if HAS_BED_PROBE
47
+  #include "probe.h"
48
+#endif
49
+
50
+#if HAS_LEVELING
51
+  #include "../feature/bedlevel/bedlevel.h"
52
+#endif
53
+
54
+#if NEED_UNHOMED_ERR && ENABLED(ULTRA_LCD)
55
+  #include "../lcd/ultralcd.h"
56
+#endif
57
+
58
+#if ENABLED(SENSORLESS_HOMING)
59
+  #include "../feature/tmc2130.h"
45 60
 #endif
46 61
 
47 62
 #define XYZ_CONSTS(type, array, CONFIG) const PROGMEM type array##_P[XYZ] = { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }
@@ -72,15 +87,85 @@ float current_position[XYZE] = { 0.0 };
72 87
  */
73 88
 float destination[XYZE] = { 0.0 };
74 89
 
90
+
75 91
 // The active extruder (tool). Set with T<extruder> command.
76 92
 uint8_t active_extruder = 0;
77 93
 
94
+// Extruder offsets
95
+#if HOTENDS > 1
96
+  float hotend_offset[XYZ][HOTENDS]; // Initialized by settings.load()
97
+#endif
98
+
78 99
 // The feedrate for the current move, often used as the default if
79 100
 // no other feedrate is specified. Overridden for special moves.
80 101
 // Set by the last G0 through G5 command's "F" parameter.
81 102
 // Functions that override this for custom moves *must always* restore it!
82 103
 float feedrate_mm_s = MMM_TO_MMS(1500.0);
83 104
 
105
+int16_t feedrate_percentage = 100;
106
+
107
+// Homing feedrate is const progmem - compare to constexpr in the header
108
+const float homing_feedrate_mm_s[4] PROGMEM = {
109
+  #if ENABLED(DELTA)
110
+    MMM_TO_MMS(HOMING_FEEDRATE_Z), MMM_TO_MMS(HOMING_FEEDRATE_Z),
111
+  #else
112
+    MMM_TO_MMS(HOMING_FEEDRATE_XY), MMM_TO_MMS(HOMING_FEEDRATE_XY),
113
+  #endif
114
+  MMM_TO_MMS(HOMING_FEEDRATE_Z), 0
115
+};
116
+
117
+// Cartesian conversion result goes here:
118
+float cartes[XYZ];
119
+
120
+// Until kinematics.cpp is created, create this here
121
+#if IS_KINEMATIC
122
+  float delta[ABC];
123
+#endif
124
+
125
+/**
126
+ * The workspace can be offset by some commands, or
127
+ * these offsets may be omitted to save on computation.
128
+ */
129
+#if HAS_WORKSPACE_OFFSET
130
+  #if HAS_POSITION_SHIFT
131
+    // The distance that XYZ has been offset by G92. Reset by G28.
132
+    float position_shift[XYZ] = { 0 };
133
+  #endif
134
+  #if HAS_HOME_OFFSET
135
+    // This offset is added to the configured home position.
136
+    // Set by M206, M428, or menu item. Saved to EEPROM.
137
+    float home_offset[XYZ] = { 0 };
138
+  #endif
139
+  #if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
140
+    // The above two are combined to save on computes
141
+    float workspace_offset[XYZ] = { 0 };
142
+  #endif
143
+#endif
144
+
145
+#if OLDSCHOOL_ABL
146
+  float xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
147
+#endif
148
+
149
+/**
150
+ * Output the current position to serial
151
+ */
152
+void report_current_position() {
153
+  SERIAL_PROTOCOLPGM("X:");
154
+  SERIAL_PROTOCOL(current_position[X_AXIS]);
155
+  SERIAL_PROTOCOLPGM(" Y:");
156
+  SERIAL_PROTOCOL(current_position[Y_AXIS]);
157
+  SERIAL_PROTOCOLPGM(" Z:");
158
+  SERIAL_PROTOCOL(current_position[Z_AXIS]);
159
+  SERIAL_PROTOCOLPGM(" E:");
160
+  SERIAL_PROTOCOL(current_position[E_AXIS]);
161
+
162
+  stepper.report_positions();
163
+
164
+  #if IS_SCARA
165
+    scara_report_positions();
166
+  #endif
167
+}
168
+
84 169
 /**
85 170
  * sync_plan_position
86 171
  *
@@ -97,6 +182,56 @@ void sync_plan_position() {
97 182
 void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
98 183
 
99 184
 /**
185
+ * Get the stepper positions in the cartes[] array.
186
+ * Forward kinematics are applied for DELTA and SCARA.
187
+ *
188
+ * The result is in the current coordinate space with
189
+ * leveling applied. The coordinates need to be run through
190
+ * unapply_leveling to obtain the "ideal" coordinates
191
+ * suitable for current_position, etc.
192
+ */
193
+void get_cartesian_from_steppers() {
194
+  #if ENABLED(DELTA)
195
+    forward_kinematics_DELTA(
196
+      stepper.get_axis_position_mm(A_AXIS),
197
+      stepper.get_axis_position_mm(B_AXIS),
198
+      stepper.get_axis_position_mm(C_AXIS)
199
+    );
200
+    cartes[X_AXIS] += LOGICAL_X_POSITION(0);
201
+    cartes[Y_AXIS] += LOGICAL_Y_POSITION(0);
202
+    cartes[Z_AXIS] += LOGICAL_Z_POSITION(0);
203
+  #elif IS_SCARA
204
+    forward_kinematics_SCARA(
205
+      stepper.get_axis_position_degrees(A_AXIS),
206
+      stepper.get_axis_position_degrees(B_AXIS)
207
+    );
208
+    cartes[X_AXIS] += LOGICAL_X_POSITION(0);
209
+    cartes[Y_AXIS] += LOGICAL_Y_POSITION(0);
210
+    cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
211
+  #else
212
+    cartes[X_AXIS] = stepper.get_axis_position_mm(X_AXIS);
213
+    cartes[Y_AXIS] = stepper.get_axis_position_mm(Y_AXIS);
214
+    cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
215
+  #endif
216
+}
217
+
218
+/**
219
+ * Set the current_position for an axis based on
220
+ * the stepper positions, removing any leveling that
221
+ * may have been applied.
222
+ */
223
+void set_current_from_steppers_for_axis(const AxisEnum axis) {
224
+  get_cartesian_from_steppers();
225
+  #if PLANNER_LEVELING
226
+    planner.unapply_leveling(cartes);
227
+  #endif
228
+  if (axis == ALL_AXES)
229
+    COPY(current_position, cartes);
230
+  else
231
+    current_position[axis] = cartes[axis];
232
+}
233
+
234
+/**
100 235
  * Move the planner to the current position from wherever it last moved
101 236
  * (or from wherever it has been told it is located).
102 237
  */
@@ -149,6 +284,167 @@ void line_to_destination(const float fr_mm_s) {
149 284
 
150 285
 #endif // IS_KINEMATIC
151 286
 
287
+/**
288
+ *  Plan a move to (X, Y, Z) and set the current_position
289
+ *  The final current_position may not be the one that was requested
290
+ */
291
+void do_blocking_move_to(const float &lx, const float &ly, const float &lz, const float &fr_mm_s/*=0.0*/) {
292
+  const float old_feedrate_mm_s = feedrate_mm_s;
293
+
294
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
295
+    if (DEBUGGING(LEVELING)) print_xyz(PSTR(">>> do_blocking_move_to"), NULL, lx, ly, lz);
296
+  #endif
297
+
298
+  #if ENABLED(DELTA)
299
+
300
+    if (!position_is_reachable_xy(lx, ly)) return;
301
+
302
+    feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
303
+
304
+    set_destination_to_current();          // sync destination at the start
305
+
306
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
307
+      if (DEBUGGING(LEVELING)) DEBUG_POS("set_destination_to_current", destination);
308
+    #endif
309
+
310
+    // when in the danger zone
311
+    if (current_position[Z_AXIS] > delta_clip_start_height) {
312
+      if (lz > delta_clip_start_height) {   // staying in the danger zone
313
+        destination[X_AXIS] = lx;           // move directly (uninterpolated)
314
+        destination[Y_AXIS] = ly;
315
+        destination[Z_AXIS] = lz;
316
+        prepare_uninterpolated_move_to_destination(); // set_current_to_destination
317
+        #if ENABLED(DEBUG_LEVELING_FEATURE)
318
+          if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
319
+        #endif
320
+        return;
321
+      }
322
+      else {
323
+        destination[Z_AXIS] = delta_clip_start_height;
324
+        prepare_uninterpolated_move_to_destination(); // set_current_to_destination
325
+        #if ENABLED(DEBUG_LEVELING_FEATURE)
326
+          if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
327
+        #endif
328
+      }
329
+    }
330
+
331
+    if (lz > current_position[Z_AXIS]) {    // raising?
332
+      destination[Z_AXIS] = lz;
333
+      prepare_uninterpolated_move_to_destination();   // set_current_to_destination
334
+      #if ENABLED(DEBUG_LEVELING_FEATURE)
335
+        if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
336
+      #endif
337
+    }
338
+
339
+    destination[X_AXIS] = lx;
340
+    destination[Y_AXIS] = ly;
341
+    prepare_move_to_destination();         // set_current_to_destination
342
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
343
+      if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position);
344
+    #endif
345
+
346
+    if (lz < current_position[Z_AXIS]) {    // lowering?
347
+      destination[Z_AXIS] = lz;
348
+      prepare_uninterpolated_move_to_destination();   // set_current_to_destination
349
+      #if ENABLED(DEBUG_LEVELING_FEATURE)
350
+        if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
351
+      #endif
352
+    }
353
+
354
+  #elif IS_SCARA
355
+
356
+    if (!position_is_reachable_xy(lx, ly)) return;
357
+
358
+    set_destination_to_current();
359
+
360
+    // If Z needs to raise, do it before moving XY
361
+    if (destination[Z_AXIS] < lz) {
362
+      destination[Z_AXIS] = lz;
363
+      prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS));
364
+    }
365
+
366
+    destination[X_AXIS] = lx;
367
+    destination[Y_AXIS] = ly;
368
+    prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S);
369
+
370
+    // If Z needs to lower, do it after moving XY
371
+    if (destination[Z_AXIS] > lz) {
372
+      destination[Z_AXIS] = lz;
373
+      prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS));
374
+    }
375
+
376
+  #else
377
+
378
+    // If Z needs to raise, do it before moving XY
379
+    if (current_position[Z_AXIS] < lz) {
380
+      feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS);
381
+      current_position[Z_AXIS] = lz;
382
+      line_to_current_position();
383
+    }
384
+
385
+    feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
386
+    current_position[X_AXIS] = lx;
387
+    current_position[Y_AXIS] = ly;
388
+    line_to_current_position();
389
+
390
+    // If Z needs to lower, do it after moving XY
391
+    if (current_position[Z_AXIS] > lz) {
392
+      feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS);
393
+      current_position[Z_AXIS] = lz;
394
+      line_to_current_position();
395
+    }
396
+
397
+  #endif
398
+
399
+  stepper.synchronize();
400
+
401
+  feedrate_mm_s = old_feedrate_mm_s;
402
+
403
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
404
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to");
405
+  #endif
406
+}
407
+void do_blocking_move_to_x(const float &lx, const float &fr_mm_s/*=0.0*/) {
408
+  do_blocking_move_to(lx, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s);
409
+}
410
+void do_blocking_move_to_z(const float &lz, const float &fr_mm_s/*=0.0*/) {
411
+  do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], lz, fr_mm_s);
412
+}
413
+void do_blocking_move_to_xy(const float &lx, const float &ly, const float &fr_mm_s/*=0.0*/) {
414
+  do_blocking_move_to(lx, ly, current_position[Z_AXIS], fr_mm_s);
415
+}
416
+
417
+//
418
+// Prepare to do endstop or probe moves
419
+// with custom feedrates.
420
+//
421
+//  - Save current feedrates
422
+//  - Reset the rate multiplier
423
+//  - Reset the command timeout
424
+//  - Enable the endstops (for endstop moves)
425
+//
426
+void bracket_probe_move(const bool before) {
427
+  static float saved_feedrate_mm_s;
428
+  static int16_t saved_feedrate_percentage;
429
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
430
+    if (DEBUGGING(LEVELING)) DEBUG_POS("bracket_probe_move", current_position);
431
+  #endif
432
+  if (before) {
433
+    saved_feedrate_mm_s = feedrate_mm_s;
434
+    saved_feedrate_percentage = feedrate_percentage;
435
+    feedrate_percentage = 100;
436
+    gcode.refresh_cmd_timeout();
437
+  }
438
+  else {
439
+    feedrate_mm_s = saved_feedrate_mm_s;
440
+    feedrate_percentage = saved_feedrate_percentage;
441
+    gcode.refresh_cmd_timeout();
442
+  }
443
+}
444
+
445
+void setup_for_endstop_or_probe_move() { bracket_probe_move(true); }
446
+void clean_up_after_endstop_or_probe_move() { bracket_probe_move(false); }
447
+
152 448
 // Software Endstops are based on the configured limits.
153 449
 float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
154 450
       soft_endstop_max[XYZ] = { X_MAX_BED, Y_MAX_BED, Z_MAX_POS };
@@ -189,73 +485,24 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
189 485
 
190 486
 #endif
191 487
 
192
-#if ENABLED(AUTO_BED_LEVELING_BILINEAR) && !IS_KINEMATIC
193
-
194
-  #define CELL_INDEX(A,V) ((RAW_##A##_POSITION(V) - bilinear_start[A##_AXIS]) * ABL_BG_FACTOR(A##_AXIS))
195
-
196
-  /**
197
-   * Prepare a bilinear-leveled linear move on Cartesian,
198
-   * splitting the move where it crosses grid borders.
199
-   */
200
-  void bilinear_line_to_destination(const float fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF);
201
-    int cx1 = CELL_INDEX(X, current_position[X_AXIS]),
202
-        cy1 = CELL_INDEX(Y, current_position[Y_AXIS]),
203
-        cx2 = CELL_INDEX(X, destination[X_AXIS]),
204
-        cy2 = CELL_INDEX(Y, destination[Y_AXIS]);
205
-    cx1 = constrain(cx1, 0, ABL_BG_POINTS_X - 2);
206
-    cy1 = constrain(cy1, 0, ABL_BG_POINTS_Y - 2);
207
-    cx2 = constrain(cx2, 0, ABL_BG_POINTS_X - 2);
208
-    cy2 = constrain(cy2, 0, ABL_BG_POINTS_Y - 2);
209
-
210
-    if (cx1 == cx2 && cy1 == cy2) {
211
-      // Start and end on same mesh square
212
-      line_to_destination(fr_mm_s);
213
-      set_current_to_destination();
214
-      return;
215
-    }
216
-
217
-    #define LINE_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist)
218
-
219
-    float normalized_dist, end[XYZE];
220
-
221
-    // Split at the left/front border of the right/top square
222
-    const int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2);
223
-    if (cx2 != cx1 && TEST(x_splits, gcx)) {
224
-      COPY(end, destination);
225
-      destination[X_AXIS] = LOGICAL_X_POSITION(bilinear_start[X_AXIS] + ABL_BG_SPACING(X_AXIS) * gcx);
226
-      normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]);
227
-      destination[Y_AXIS] = LINE_SEGMENT_END(Y);
228
-      CBI(x_splits, gcx);
229
-    }
230
-    else if (cy2 != cy1 && TEST(y_splits, gcy)) {
231
-      COPY(end, destination);
232
-      destination[Y_AXIS] = LOGICAL_Y_POSITION(bilinear_start[Y_AXIS] + ABL_BG_SPACING(Y_AXIS) * gcy);
233
-      normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]);
234
-      destination[X_AXIS] = LINE_SEGMENT_END(X);
235
-      CBI(y_splits, gcy);
236
-    }
237
-    else {
238
-      // Already split on a border
239
-      line_to_destination(fr_mm_s);
240
-      set_current_to_destination();
241
-      return;
242
-    }
243
-
244
-    destination[Z_AXIS] = LINE_SEGMENT_END(Z);
245
-    destination[E_AXIS] = LINE_SEGMENT_END(E);
246
-
247
-    // Do the split and look for more borders
248
-    bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
249
-
250
-    // Restore destination from stack
251
-    COPY(destination, end);
252
-    bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
253
-  }
254
-
255
-#endif // AUTO_BED_LEVELING_BILINEAR
256
-
257 488
 #if IS_KINEMATIC && !UBL_DELTA
258 489
 
490
+  #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
491
+    #if ENABLED(DELTA)
492
+      #define ADJUST_DELTA(V) \
493
+        if (planner.abl_enabled) { \
494
+          const float zadj = bilinear_z_offset(V); \
495
+          delta[A_AXIS] += zadj; \
496
+          delta[B_AXIS] += zadj; \
497
+          delta[C_AXIS] += zadj; \
498
+        }
499
+    #else
500
+      #define ADJUST_DELTA(V) if (planner.abl_enabled) { delta[Z_AXIS] += bilinear_z_offset(V); }
501
+    #endif
502
+  #else
503
+    #define ADJUST_DELTA(V) NOOP
504
+  #endif
505
+
259 506
   /**
260 507
    * Prepare a linear move in a DELTA or SCARA setup.
261 508
    *
@@ -572,3 +819,453 @@ void prepare_move_to_destination() {
572 819
 
573 820
   set_current_to_destination();
574 821
 }
822
+
823
+#if NEED_UNHOMED_ERR
824
+
825
+  bool axis_unhomed_error(const bool x/*=true*/, const bool y/*=true*/, const bool z/*=true*/) {
826
+    #if ENABLED(HOME_AFTER_DEACTIVATE)
827
+      const bool xx = x && !axis_known_position[X_AXIS],
828
+                 yy = y && !axis_known_position[Y_AXIS],
829
+                 zz = z && !axis_known_position[Z_AXIS];
830
+    #else
831
+      const bool xx = x && !axis_homed[X_AXIS],
832
+                 yy = y && !axis_homed[Y_AXIS],
833
+                 zz = z && !axis_homed[Z_AXIS];
834
+    #endif
835
+    if (xx || yy || zz) {
836
+      SERIAL_ECHO_START();
837
+      SERIAL_ECHOPGM(MSG_HOME " ");
838
+      if (xx) SERIAL_ECHOPGM(MSG_X);
839
+      if (yy) SERIAL_ECHOPGM(MSG_Y);
840
+      if (zz) SERIAL_ECHOPGM(MSG_Z);
841
+      SERIAL_ECHOLNPGM(" " MSG_FIRST);
842
+
843
+      #if ENABLED(ULTRA_LCD)
844
+        lcd_status_printf_P(0, PSTR(MSG_HOME " %s%s%s " MSG_FIRST), xx ? MSG_X : "", yy ? MSG_Y : "", zz ? MSG_Z : "");
845
+      #endif
846
+      return true;
847
+    }
848
+    return false;
849
+  }
850
+
851
+#endif
852
+
853
+/**
854
+ * The homing feedrate may vary
855
+ */
856
+inline float get_homing_bump_feedrate(const AxisEnum axis) {
857
+  static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR;
858
+  uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]);
859
+  if (hbd < 1) {
860
+    hbd = 10;
861
+    SERIAL_ECHO_START();
862
+    SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1");
863
+  }
864
+  return homing_feedrate(axis) / hbd;
865
+}
866
+
867
+/**
868
+ * Home an individual linear axis
869
+ */
870
+static void do_homing_move(const AxisEnum axis, const float distance, const float fr_mm_s=0.0) {
871
+
872
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
873
+    if (DEBUGGING(LEVELING)) {
874
+      SERIAL_ECHOPAIR(">>> do_homing_move(", axis_codes[axis]);
875
+      SERIAL_ECHOPAIR(", ", distance);
876
+      SERIAL_ECHOPAIR(", ", fr_mm_s);
877
+      SERIAL_CHAR(')');
878
+      SERIAL_EOL();
879
+    }
880
+  #endif
881
+
882
+  #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH)
883
+    const bool deploy_bltouch = (axis == Z_AXIS && distance < 0);
884
+    if (deploy_bltouch) set_bltouch_deployed(true);
885
+  #endif
886
+
887
+  #if QUIET_PROBING
888
+    if (axis == Z_AXIS) probing_pause(true);
889
+  #endif
890
+
891
+  // Tell the planner we're at Z=0
892
+  current_position[axis] = 0;
893
+
894
+  #if IS_SCARA
895
+    SYNC_PLAN_POSITION_KINEMATIC();
896
+    current_position[axis] = distance;
897
+    inverse_kinematics(current_position);
898
+    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);
899
+  #else
900
+    sync_plan_position();
901
+    current_position[axis] = distance;
902
+    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);
903
+  #endif
904
+
905
+  stepper.synchronize();
906
+
907
+  #if QUIET_PROBING
908
+    if (axis == Z_AXIS) probing_pause(false);
909
+  #endif
910
+
911
+  #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH)
912
+    if (deploy_bltouch) set_bltouch_deployed(false);
913
+  #endif
914
+
915
+  endstops.hit_on_purpose();
916
+
917
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
918
+    if (DEBUGGING(LEVELING)) {
919
+      SERIAL_ECHOPAIR("<<< do_homing_move(", axis_codes[axis]);
920
+      SERIAL_CHAR(')');
921
+      SERIAL_EOL();
922
+    }
923
+  #endif
924
+}
925
+
926
+/**
927
+ * Set an axis' current position to its home position (after homing).
928
+ *
929
+ * For Core and Cartesian robots this applies one-to-one when an
930
+ * individual axis has been homed.
931
+ *
932
+ * DELTA should wait until all homing is done before setting the XYZ
933
+ * current_position to home, because homing is a single operation.
934
+ * In the case where the axis positions are already known and previously
935
+ * homed, DELTA could home to X or Y individually by moving either one
936
+ * to the center. However, homing Z always homes XY and Z.
937
+ *
938
+ * SCARA should wait until all XY homing is done before setting the XY
939
+ * current_position to home, because neither X nor Y is at home until
940
+ * both are at home. Z can however be homed individually.
941
+ *
942
+ * Callers must sync the planner position after calling this!
943
+ */
944
+void set_axis_is_at_home(const AxisEnum axis) {
945
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
946
+    if (DEBUGGING(LEVELING)) {
947
+      SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis_codes[axis]);
948
+      SERIAL_CHAR(')');
949
+      SERIAL_EOL();
950
+    }
951
+  #endif
952
+
953
+  axis_known_position[axis] = axis_homed[axis] = true;
954
+
955
+  #if HAS_POSITION_SHIFT
956
+    position_shift[axis] = 0;
957
+    update_software_endstops(axis);
958
+  #endif
959
+
960
+  #if ENABLED(DUAL_X_CARRIAGE)
961
+    if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) {
962
+      current_position[X_AXIS] = x_home_pos(active_extruder);
963
+      return;
964
+    }
965
+  #endif
966
+
967
+  #if ENABLED(MORGAN_SCARA)
968
+    scara_set_axis_is_at_home(axis);
969
+  #else
970
+    current_position[axis] = LOGICAL_POSITION(base_home_pos(axis), axis);
971
+  #endif
972
+
973
+  /**
974
+   * Z Probe Z Homing? Account for the probe's Z offset.
975
+   */
976
+  #if HAS_BED_PROBE && Z_HOME_DIR < 0
977
+    if (axis == Z_AXIS) {
978
+      #if HOMING_Z_WITH_PROBE
979
+
980
+        current_position[Z_AXIS] -= zprobe_zoffset;
981
+
982
+        #if ENABLED(DEBUG_LEVELING_FEATURE)
983
+          if (DEBUGGING(LEVELING)) {
984
+            SERIAL_ECHOLNPGM("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***");
985
+            SERIAL_ECHOLNPAIR("> zprobe_zoffset = ", zprobe_zoffset);
986
+          }
987
+        #endif
988
+
989
+      #elif ENABLED(DEBUG_LEVELING_FEATURE)
990
+
991
+        if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("*** Z HOMED TO ENDSTOP (Z_MIN_PROBE_ENDSTOP) ***");
992
+
993
+      #endif
994
+    }
995
+  #endif
996
+
997
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
998
+    if (DEBUGGING(LEVELING)) {
999
+      #if HAS_HOME_OFFSET
1000
+        SERIAL_ECHOPAIR("> home_offset[", axis_codes[axis]);
1001
+        SERIAL_ECHOLNPAIR("] = ", home_offset[axis]);
1002
+      #endif
1003
+      DEBUG_POS("", current_position);
1004
+      SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis_codes[axis]);
1005
+      SERIAL_CHAR(')');
1006
+      SERIAL_EOL();
1007
+    }
1008
+  #endif
1009
+
1010
+  #if ENABLED(I2C_POSITION_ENCODERS)
1011
+    I2CPEM.homed(axis);
1012
+  #endif
1013
+}
1014
+
1015
+/**
1016
+ * Home an individual "raw axis" to its endstop.
1017
+ * This applies to XYZ on Cartesian and Core robots, and
1018
+ * to the individual ABC steppers on DELTA and SCARA.
1019
+ *
1020
+ * At the end of the procedure the axis is marked as
1021
+ * homed and the current position of that axis is updated.
1022
+ * Kinematic robots should wait till all axes are homed
1023
+ * before updating the current position.
1024
+ */
1025
+
1026
+void homeaxis(const AxisEnum axis) {
1027
+
1028
+  #if IS_SCARA
1029
+    // Only Z homing (with probe) is permitted
1030
+    if (axis != Z_AXIS) { BUZZ(100, 880); return; }
1031
+  #else
1032
+    #define CAN_HOME(A) \
1033
+      (axis == A##_AXIS && ((A##_MIN_PIN > -1 && A##_HOME_DIR < 0) || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0)))
1034
+    if (!CAN_HOME(X) && !CAN_HOME(Y) && !CAN_HOME(Z)) return;
1035
+  #endif
1036
+
1037
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
1038
+    if (DEBUGGING(LEVELING)) {
1039
+      SERIAL_ECHOPAIR(">>> homeaxis(", axis_codes[axis]);
1040
+      SERIAL_CHAR(')');
1041
+      SERIAL_EOL();
1042
+    }
1043
+  #endif
1044
+
1045
+  const int axis_home_dir =
1046
+    #if ENABLED(DUAL_X_CARRIAGE)
1047
+      (axis == X_AXIS) ? x_home_dir(active_extruder) :
1048
+    #endif
1049
+    home_dir(axis);
1050
+
1051
+  // Homing Z towards the bed? Deploy the Z probe or endstop.
1052
+  #if HOMING_Z_WITH_PROBE
1053
+    if (axis == Z_AXIS && DEPLOY_PROBE()) return;
1054
+  #endif
1055
+
1056
+  // Set a flag for Z motor locking
1057
+  #if ENABLED(Z_DUAL_ENDSTOPS)
1058
+    if (axis == Z_AXIS) stepper.set_homing_flag(true);
1059
+  #endif
1060
+
1061
+  // Disable stealthChop if used. Enable diag1 pin on driver.
1062
+  #if ENABLED(SENSORLESS_HOMING)
1063
+    #if ENABLED(X_IS_TMC2130)
1064
+      if (axis == X_AXIS) tmc2130_sensorless_homing(stepperX);
1065
+    #endif
1066
+    #if ENABLED(Y_IS_TMC2130)
1067
+      if (axis == Y_AXIS) tmc2130_sensorless_homing(stepperY);
1068
+    #endif
1069
+  #endif
1070
+
1071
+  // Fast move towards endstop until triggered
1072
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
1073
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 1 Fast:");
1074
+  #endif
1075
+  do_homing_move(axis, 1.5 * max_length(axis) * axis_home_dir);
1076
+
1077
+  // When homing Z with probe respect probe clearance
1078
+  const float bump = axis_home_dir * (
1079
+    #if HOMING_Z_WITH_PROBE
1080
+      (axis == Z_AXIS) ? max(Z_CLEARANCE_BETWEEN_PROBES, home_bump_mm(Z_AXIS)) :
1081
+    #endif
1082
+    home_bump_mm(axis)
1083
+  );
1084
+
1085
+  // If a second homing move is configured...
1086
+  if (bump) {
1087
+    // Move away from the endstop by the axis HOME_BUMP_MM
1088
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
1089
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Move Away:");
1090
+    #endif
1091
+    do_homing_move(axis, -bump);
1092
+
1093
+    // Slow move towards endstop until triggered
1094
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
1095
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 2 Slow:");
1096
+    #endif
1097
+    do_homing_move(axis, 2 * bump, get_homing_bump_feedrate(axis));
1098
+  }
1099
+
1100
+  #if ENABLED(Z_DUAL_ENDSTOPS)
1101
+    if (axis == Z_AXIS) {
1102
+      float adj = FABS(z_endstop_adj);
1103
+      bool lockZ1;
1104
+      if (axis_home_dir > 0) {
1105
+        adj = -adj;
1106
+        lockZ1 = (z_endstop_adj > 0);
1107
+      }
1108
+      else
1109
+        lockZ1 = (z_endstop_adj < 0);
1110
+
1111
+      if (lockZ1) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
1112
+
1113
+      // Move to the adjusted endstop height
1114
+      do_homing_move(axis, adj);
1115
+
1116
+      if (lockZ1) stepper.set_z_lock(false); else stepper.set_z2_lock(false);
1117
+      stepper.set_homing_flag(false);
1118
+    } // Z_AXIS
1119
+  #endif
1120
+
1121
+  #if IS_SCARA
1122
+
1123
+    set_axis_is_at_home(axis);
1124
+    SYNC_PLAN_POSITION_KINEMATIC();
1125
+
1126
+  #elif ENABLED(DELTA)
1127
+
1128
+    // Delta has already moved all three towers up in G28
1129
+    // so here it re-homes each tower in turn.
1130
+    // Delta homing treats the axes as normal linear axes.
1131
+
1132
+    // retrace by the amount specified in delta_endstop_adj + additional 0.1mm in order to have minimum steps
1133
+    if (delta_endstop_adj[axis] * Z_HOME_DIR <= 0) {
1134
+      #if ENABLED(DEBUG_LEVELING_FEATURE)
1135
+        if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("delta_endstop_adj:");
1136
+      #endif
1137
+      do_homing_move(axis, delta_endstop_adj[axis] - 0.1);
1138
+    }
1139
+
1140
+  #else
1141
+
1142
+    // For cartesian/core machines,
1143
+    // set the axis to its home position
1144
+    set_axis_is_at_home(axis);
1145
+    sync_plan_position();
1146
+
1147
+    destination[axis] = current_position[axis];
1148
+
1149
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
1150
+      if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position);
1151
+    #endif
1152
+
1153
+  #endif
1154
+
1155
+  // Re-enable stealthChop if used. Disable diag1 pin on driver.
1156
+  #if ENABLED(SENSORLESS_HOMING)
1157
+    #if ENABLED(X_IS_TMC2130)
1158
+      if (axis == X_AXIS) tmc2130_sensorless_homing(stepperX, false);
1159
+    #endif
1160
+    #if ENABLED(Y_IS_TMC2130)
1161
+      if (axis == Y_AXIS) tmc2130_sensorless_homing(stepperY, false);
1162
+    #endif
1163
+  #endif
1164
+
1165
+  // Put away the Z probe
1166
+  #if HOMING_Z_WITH_PROBE
1167
+    if (axis == Z_AXIS && STOW_PROBE()) return;
1168
+  #endif
1169
+
1170
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
1171
+    if (DEBUGGING(LEVELING)) {
1172
+      SERIAL_ECHOPAIR("<<< homeaxis(", axis_codes[axis]);
1173
+      SERIAL_CHAR(')');
1174
+      SERIAL_EOL();
1175
+    }
1176
+  #endif
1177
+} // homeaxis()
1178
+
1179
+#if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE)
1180
+
1181
+  /**
1182
+   * Software endstops can be used to monitor the open end of
1183
+   * an axis that has a hardware endstop on the other end. Or
1184
+   * they can prevent axes from moving past endstops and grinding.
1185
+   *
1186
+   * To keep doing their job as the coordinate system changes,
1187
+   * the software endstop positions must be refreshed to remain
1188
+   * at the same positions relative to the machine.
1189
+   */
1190
+  void update_software_endstops(const AxisEnum axis) {
1191
+    const float offs = 0.0
1192
+      #if HAS_HOME_OFFSET
1193
+        + home_offset[axis]
1194
+      #endif
1195
+      #if HAS_POSITION_SHIFT
1196
+        + position_shift[axis]
1197
+      #endif
1198
+    ;
1199
+
1200
+    #if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
1201
+      workspace_offset[axis] = offs;
1202
+    #endif
1203
+
1204
+    #if ENABLED(DUAL_X_CARRIAGE)
1205
+      if (axis == X_AXIS) {
1206
+
1207
+        // In Dual X mode hotend_offset[X] is T1's home position
1208
+        float dual_max_x = max(hotend_offset[X_AXIS][1], X2_MAX_POS);
1209
+
1210
+        if (active_extruder != 0) {
1211
+          // T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger)
1212
+          soft_endstop_min[X_AXIS] = X2_MIN_POS + offs;
1213
+          soft_endstop_max[X_AXIS] = dual_max_x + offs;
1214
+        }
1215
+        else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
1216
+          // In Duplication Mode, T0 can move as far left as X_MIN_POS
1217
+          // but not so far to the right that T1 would move past the end
1218
+          soft_endstop_min[X_AXIS] = base_min_pos(X_AXIS) + offs;
1219
+          soft_endstop_max[X_AXIS] = min(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset) + offs;
1220
+        }
1221
+        else {
1222
+          // In other modes, T0 can move from X_MIN_POS to X_MAX_POS
1223
+          soft_endstop_min[axis] = base_min_pos(axis) + offs;
1224
+          soft_endstop_max[axis] = base_max_pos(axis) + offs;
1225
+        }
1226
+      }
1227
+    #elif ENABLED(DELTA)
1228
+      soft_endstop_min[axis] = base_min_pos(axis) + (axis == Z_AXIS ? 0 : offs);
1229
+      soft_endstop_max[axis] = base_max_pos(axis) + offs;
1230
+    #else
1231
+      soft_endstop_min[axis] = base_min_pos(axis) + offs;
1232
+      soft_endstop_max[axis] = base_max_pos(axis) + offs;
1233
+    #endif
1234
+
1235
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
1236
+      if (DEBUGGING(LEVELING)) {
1237
+        SERIAL_ECHOPAIR("For ", axis_codes[axis]);
1238
+        #if HAS_HOME_OFFSET
1239
+          SERIAL_ECHOPAIR(" axis:\n home_offset = ", home_offset[axis]);
1240
+        #endif
1241
+        #if HAS_POSITION_SHIFT
1242
+          SERIAL_ECHOPAIR("\n position_shift = ", position_shift[axis]);
1243
+        #endif
1244
+        SERIAL_ECHOPAIR("\n soft_endstop_min = ", soft_endstop_min[axis]);
1245
+        SERIAL_ECHOLNPAIR("\n soft_endstop_max = ", soft_endstop_max[axis]);
1246
+      }
1247
+    #endif
1248
+
1249
+    #if ENABLED(DELTA)
1250
+      if (axis == Z_AXIS)
1251
+        delta_clip_start_height = soft_endstop_max[axis] - delta_safe_distance_from_top();
1252
+    #endif
1253
+  }
1254
+
1255
+#endif // HAS_WORKSPACE_OFFSET || DUAL_X_CARRIAGE
1256
+
1257
+#if HAS_M206_COMMAND
1258
+  /**
1259
+   * Change the home offset for an axis, update the current
1260
+   * position and the software endstops to retain the same
1261
+   * relative distance to the new home.
1262
+   *
1263
+   * Since this changes the current_position, code should
1264
+   * call sync_plan_position soon after this.
1265
+   */
1266
+  void set_home_offset(const AxisEnum axis, const float v) {
1267
+    current_position[axis] += v - home_offset[axis];
1268
+    home_offset[axis] = v;
1269
+    update_software_endstops(axis);
1270
+  }
1271
+#endif // HAS_M206_COMMAND

+ 87
- 11
Marlin/src/module/motion.h View File

@@ -32,20 +32,53 @@
32 32
 
33 33
 #include "../inc/MarlinConfig.h"
34 34
 
35
-//#include "../HAL/HAL.h"
36
-
37
-// #if ENABLED(DELTA)
38
-//   #include "../module/delta.h"
39
-// #endif
35
+#if IS_SCARA
36
+  #include "../module/scara.h"
37
+#endif
40 38
 
41 39
 extern bool relative_mode;
42 40
 
43
-extern float current_position[XYZE], destination[XYZE];
41
+extern float current_position[XYZE],  // High-level current tool position
42
+             destination[XYZE];       // Destination for a move
43
+
44
+// Scratch space for a cartesian result
45
+extern float cartes[XYZ];
46
+
47
+// Until kinematics.cpp is created, declare this here
48
+#if IS_KINEMATIC
49
+  extern float delta[ABC];
50
+#endif
51
+
52
+#if OLDSCHOOL_ABL
53
+  extern float xy_probe_feedrate_mm_s;
54
+  #define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s
55
+#elif defined(XY_PROBE_SPEED)
56
+  #define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_SPEED)
57
+#else
58
+  #define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE()
59
+#endif
60
+
61
+/**
62
+ * Feed rates are often configured with mm/m
63
+ * but the planner and stepper like mm/s units.
64
+ */
65
+extern const float homing_feedrate_mm_s[4];
66
+FORCE_INLINE float homing_feedrate(const AxisEnum a) { return pgm_read_float(&homing_feedrate_mm_s[a]); }
44 67
 
45 68
 extern float feedrate_mm_s;
46 69
 
70
+/**
71
+ * Feedrate scaling and conversion
72
+ */
73
+extern int16_t feedrate_percentage;
74
+#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
75
+
47 76
 extern uint8_t active_extruder;
48 77
 
78
+#if HOTENDS > 1
79
+  extern float hotend_offset[XYZ][HOTENDS];
80
+#endif
81
+
49 82
 extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
50 83
 
51 84
 FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float_near(p); }
@@ -71,9 +104,14 @@ XYZ_DEFS(signed char, home_dir, HOME_DIR);
71 104
   #define clamp_to_software_endstops(x) NOOP
72 105
 #endif
73 106
 
107
+void report_current_position();
108
+
74 109
 inline void set_current_to_destination() { COPY(current_position, destination); }
75 110
 inline void set_destination_to_current() { COPY(destination, current_position); }
76 111
 
112
+void get_cartesian_from_steppers();
113
+void set_current_from_steppers_for_axis(const AxisEnum axis);
114
+
77 115
 /**
78 116
  * sync_plan_position
79 117
  *
@@ -110,7 +148,35 @@ inline void line_to_destination() { line_to_destination(feedrate_mm_s); }
110 148
 
111 149
 void prepare_move_to_destination();
112 150
 
113
-void clamp_to_software_endstops(float target[XYZ]);
151
+/**
152
+ * Blocking movement and shorthand functions
153
+ */
154
+void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s=0.0);
155
+void do_blocking_move_to_x(const float &x, const float &fr_mm_s=0.0);
156
+void do_blocking_move_to_z(const float &z, const float &fr_mm_s=0.0);
157
+void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s=0.0);
158
+
159
+void setup_for_endstop_or_probe_move();
160
+void clean_up_after_endstop_or_probe_move();
161
+
162
+void bracket_probe_move(const bool before);
163
+void setup_for_endstop_or_probe_move();
164
+void clean_up_after_endstop_or_probe_move();
165
+
166
+//
167
+// Homing
168
+//
169
+
170
+#define NEED_UNHOMED_ERR (HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) || ENABLED(DELTA_AUTO_CALIBRATION))
171
+
172
+#if NEED_UNHOMED_ERR
173
+  bool axis_unhomed_error(const bool x=true, const bool y=true, const bool z=true);
174
+#endif
175
+
176
+void set_axis_is_at_home(const AxisEnum axis);
177
+
178
+void homeaxis(const AxisEnum axis);
179
+#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
114 180
 
115 181
 //
116 182
 // Macros
@@ -162,10 +228,6 @@ void clamp_to_software_endstops(float target[XYZ]);
162 228
 
163 229
 #if IS_KINEMATIC // (DELTA or SCARA)
164 230
 
165
-  #if IS_SCARA
166
-    extern const float L1, L2;
167
-  #endif
168
-
169 231
   inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) {
170 232
     #if ENABLED(DELTA)
171 233
       return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS);
@@ -214,10 +276,16 @@ FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) {
214 276
   return position_is_reachable_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly));
215 277
 }
216 278
 
279
+/**
280
+ * Dual X Carriage / Dual Nozzle
281
+ */
217 282
 #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
218 283
   extern bool extruder_duplication_enabled;       // Used in Dual X mode 2
219 284
 #endif
220 285
 
286
+/**
287
+ * Dual X Carriage
288
+ */
221 289
 #if ENABLED(DUAL_X_CARRIAGE)
222 290
 
223 291
   extern DualXMode dual_x_carriage_mode;
@@ -234,4 +302,12 @@ FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) {
234 302
 
235 303
 #endif // DUAL_X_CARRIAGE
236 304
 
305
+#if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE)
306
+  void update_software_endstops(const AxisEnum axis);
307
+#endif
308
+
309
+#if HAS_M206_COMMAND
310
+  void set_home_offset(const AxisEnum axis, const float v);
311
+#endif
312
+
237 313
 #endif // MOTION_H

+ 8
- 10
Marlin/src/module/planner.cpp View File

@@ -64,13 +64,12 @@
64 64
 #include "../module/temperature.h"
65 65
 #include "../lcd/ultralcd.h"
66 66
 #include "../core/language.h"
67
-#include "../feature/ubl/ubl.h"
68 67
 #include "../gcode/parser.h"
69 68
 
70 69
 #include "../Marlin.h"
71 70
 
72
-#if ENABLED(MESH_BED_LEVELING)
73
-  #include "../feature/mbl/mesh_bed_leveling.h"
71
+#if HAS_LEVELING
72
+  #include "../feature/bedlevel/bedlevel.h"
74 73
 #endif
75 74
 
76 75
 Planner planner;
@@ -107,12 +106,11 @@ float Planner::min_feedrate_mm_s,
107 106
       Planner::max_jerk[XYZE],       // The largest speed change requiring no acceleration
108 107
       Planner::min_travel_feedrate_mm_s;
109 108
 
110
-#if HAS_ABL
109
+#if OLDSCHOOL_ABL
111 110
   bool Planner::abl_enabled = false; // Flag that auto bed leveling is enabled
112
-#endif
113
-
114
-#if ABL_PLANAR
115
-  matrix_3x3 Planner::bed_level_matrix; // Transform to compensate for bed level
111
+  #if ABL_PLANAR
112
+    matrix_3x3 Planner::bed_level_matrix; // Transform to compensate for bed level
113
+  #endif
116 114
 #endif
117 115
 
118 116
 #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
@@ -546,7 +544,7 @@ void Planner::check_axes_activity() {
546 544
       #endif // FADE
547 545
     #endif // UBL
548 546
 
549
-    #if HAS_ABL
547
+    #if OLDSCHOOL_ABL
550 548
       if (!abl_enabled) return;
551 549
     #endif
552 550
 
@@ -634,7 +632,7 @@ void Planner::check_axes_activity() {
634 632
 
635 633
     #endif
636 634
 
637
-    #if HAS_ABL
635
+    #if OLDSCHOOL_ABL
638 636
       if (!abl_enabled) return;
639 637
     #endif
640 638
 

+ 7
- 1
Marlin/src/module/planner.h View File

@@ -34,6 +34,12 @@
34 34
 
35 35
 #include "../Marlin.h"
36 36
 
37
+#include "motion.h"
38
+
39
+#if ENABLED(DELTA)
40
+  #include "delta.h"
41
+#endif
42
+
37 43
 #if HAS_ABL
38 44
   #include "../libs/vector_3.h"
39 45
 #endif
@@ -159,7 +165,7 @@ class Planner {
159 165
                  max_jerk[XYZE],       // The largest speed change requiring no acceleration
160 166
                  min_travel_feedrate_mm_s;
161 167
 
162
-    #if HAS_ABL
168
+    #if OLDSCHOOL_ABL
163 169
       static bool abl_enabled;              // Flag that bed leveling is enabled
164 170
       #if ABL_PLANAR
165 171
         static matrix_3x3 bed_level_matrix; // Transform to compensate for bed level

+ 709
- 0
Marlin/src/module/probe.cpp View File

@@ -0,0 +1,709 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * probe.cpp
25
+ */
26
+
27
+#include "../inc/MarlinConfig.h"
28
+
29
+#if HAS_BED_PROBE
30
+
31
+#include "probe.h"
32
+#include "motion.h"
33
+#include "temperature.h"
34
+#include "endstops.h"
35
+
36
+#include "../gcode/gcode.h"
37
+#include "../lcd/ultralcd.h"
38
+
39
+#include "../Marlin.h"
40
+
41
+#if HAS_LEVELING
42
+  #include "../feature/bedlevel/bedlevel.h"
43
+#endif
44
+
45
+#if ENABLED(DELTA)
46
+  #include "../module/delta.h"
47
+#endif
48
+
49
+float zprobe_zoffset; // Initialized by settings.load()
50
+
51
+#if HAS_Z_SERVO_ENDSTOP
52
+  const int z_servo_angle[2] = Z_SERVO_ANGLES;
53
+#endif
54
+
55
+/**
56
+ * Raise Z to a minimum height to make room for a probe to move
57
+ */
58
+inline void do_probe_raise(const float z_raise) {
59
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
60
+    if (DEBUGGING(LEVELING)) {
61
+      SERIAL_ECHOPAIR("do_probe_raise(", z_raise);
62
+      SERIAL_CHAR(')');
63
+      SERIAL_EOL();
64
+    }
65
+  #endif
66
+
67
+  float z_dest = z_raise;
68
+  if (zprobe_zoffset < 0) z_dest -= zprobe_zoffset;
69
+
70
+  if (z_dest > current_position[Z_AXIS])
71
+    do_blocking_move_to_z(z_dest);
72
+}
73
+
74
+#if ENABLED(Z_PROBE_SLED)
75
+
76
+  #ifndef SLED_DOCKING_OFFSET
77
+    #define SLED_DOCKING_OFFSET 0
78
+  #endif
79
+
80
+  /**
81
+   * Method to dock/undock a sled designed by Charles Bell.
82
+   *
83
+   * stow[in]     If false, move to MAX_X and engage the solenoid
84
+   *              If true, move to MAX_X and release the solenoid
85
+   */
86
+  static void dock_sled(bool stow) {
87
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
88
+      if (DEBUGGING(LEVELING)) {
89
+        SERIAL_ECHOPAIR("dock_sled(", stow);
90
+        SERIAL_CHAR(')');
91
+        SERIAL_EOL();
92
+      }
93
+    #endif
94
+
95
+    // Dock sled a bit closer to ensure proper capturing
96
+    do_blocking_move_to_x(X_MAX_POS + SLED_DOCKING_OFFSET - ((stow) ? 1 : 0));
97
+
98
+    #if HAS_SOLENOID_1 && DISABLED(EXT_SOLENOID)
99
+      WRITE(SOL1_PIN, !stow); // switch solenoid
100
+    #endif
101
+  }
102
+
103
+#elif ENABLED(Z_PROBE_ALLEN_KEY)
104
+
105
+  FORCE_INLINE void do_blocking_move_to(const float logical[XYZ], const float &fr_mm_s) {
106
+    do_blocking_move_to(logical[X_AXIS], logical[Y_AXIS], logical[Z_AXIS], fr_mm_s);
107
+  }
108
+
109
+  void run_deploy_moves_script() {
110
+    #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Z)
111
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_X
112
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_1_X current_position[X_AXIS]
113
+      #endif
114
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_Y
115
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_1_Y current_position[Y_AXIS]
116
+      #endif
117
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_Z
118
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_1_Z current_position[Z_AXIS]
119
+      #endif
120
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE
121
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0
122
+      #endif
123
+      const float deploy_1[] = { Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z };
124
+      do_blocking_move_to(deploy_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE));
125
+    #endif
126
+    #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Z)
127
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_X
128
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_2_X current_position[X_AXIS]
129
+      #endif
130
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_Y
131
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_2_Y current_position[Y_AXIS]
132
+      #endif
133
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_Z
134
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_2_Z current_position[Z_AXIS]
135
+      #endif
136
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE
137
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0
138
+      #endif
139
+      const float deploy_2[] = { Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z };
140
+      do_blocking_move_to(deploy_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE));
141
+    #endif
142
+    #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Z)
143
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_X
144
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_3_X current_position[X_AXIS]
145
+      #endif
146
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_Y
147
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_3_Y current_position[Y_AXIS]
148
+      #endif
149
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_Z
150
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z current_position[Z_AXIS]
151
+      #endif
152
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE
153
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0
154
+      #endif
155
+      const float deploy_3[] = { Z_PROBE_ALLEN_KEY_DEPLOY_3_X, Z_PROBE_ALLEN_KEY_DEPLOY_3_Y, Z_PROBE_ALLEN_KEY_DEPLOY_3_Z };
156
+      do_blocking_move_to(deploy_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE));
157
+    #endif
158
+    #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Z)
159
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_X
160
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_4_X current_position[X_AXIS]
161
+      #endif
162
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_Y
163
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_4_Y current_position[Y_AXIS]
164
+      #endif
165
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_Z
166
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_4_Z current_position[Z_AXIS]
167
+      #endif
168
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE
169
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0
170
+      #endif
171
+      const float deploy_4[] = { Z_PROBE_ALLEN_KEY_DEPLOY_4_X, Z_PROBE_ALLEN_KEY_DEPLOY_4_Y, Z_PROBE_ALLEN_KEY_DEPLOY_4_Z };
172
+      do_blocking_move_to(deploy_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE));
173
+    #endif
174
+    #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Z)
175
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_X
176
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_5_X current_position[X_AXIS]
177
+      #endif
178
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_Y
179
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_5_Y current_position[Y_AXIS]
180
+      #endif
181
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_Z
182
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_5_Z current_position[Z_AXIS]
183
+      #endif
184
+      #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE
185
+        #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0
186
+      #endif
187
+      const float deploy_5[] = { Z_PROBE_ALLEN_KEY_DEPLOY_5_X, Z_PROBE_ALLEN_KEY_DEPLOY_5_Y, Z_PROBE_ALLEN_KEY_DEPLOY_5_Z };
188
+      do_blocking_move_to(deploy_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE));
189
+    #endif
190
+  }
191
+
192
+  void run_stow_moves_script() {
193
+    #if defined(Z_PROBE_ALLEN_KEY_STOW_1_X) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Z)
194
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_1_X
195
+        #define Z_PROBE_ALLEN_KEY_STOW_1_X current_position[X_AXIS]
196
+      #endif
197
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_1_Y
198
+        #define Z_PROBE_ALLEN_KEY_STOW_1_Y current_position[Y_AXIS]
199
+      #endif
200
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_1_Z
201
+        #define Z_PROBE_ALLEN_KEY_STOW_1_Z current_position[Z_AXIS]
202
+      #endif
203
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE
204
+        #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0
205
+      #endif
206
+      const float stow_1[] = { Z_PROBE_ALLEN_KEY_STOW_1_X, Z_PROBE_ALLEN_KEY_STOW_1_Y, Z_PROBE_ALLEN_KEY_STOW_1_Z };
207
+      do_blocking_move_to(stow_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE));
208
+    #endif
209
+    #if defined(Z_PROBE_ALLEN_KEY_STOW_2_X) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Z)
210
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_2_X
211
+        #define Z_PROBE_ALLEN_KEY_STOW_2_X current_position[X_AXIS]
212
+      #endif
213
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_2_Y
214
+        #define Z_PROBE_ALLEN_KEY_STOW_2_Y current_position[Y_AXIS]
215
+      #endif
216
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_2_Z
217
+        #define Z_PROBE_ALLEN_KEY_STOW_2_Z current_position[Z_AXIS]
218
+      #endif
219
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE
220
+        #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0
221
+      #endif
222
+      const float stow_2[] = { Z_PROBE_ALLEN_KEY_STOW_2_X, Z_PROBE_ALLEN_KEY_STOW_2_Y, Z_PROBE_ALLEN_KEY_STOW_2_Z };
223
+      do_blocking_move_to(stow_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE));
224
+    #endif
225
+    #if defined(Z_PROBE_ALLEN_KEY_STOW_3_X) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Z)
226
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_3_X
227
+        #define Z_PROBE_ALLEN_KEY_STOW_3_X current_position[X_AXIS]
228
+      #endif
229
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_3_Y
230
+        #define Z_PROBE_ALLEN_KEY_STOW_3_Y current_position[Y_AXIS]
231
+      #endif
232
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_3_Z
233
+        #define Z_PROBE_ALLEN_KEY_STOW_3_Z current_position[Z_AXIS]
234
+      #endif
235
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE
236
+        #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0
237
+      #endif
238
+      const float stow_3[] = { Z_PROBE_ALLEN_KEY_STOW_3_X, Z_PROBE_ALLEN_KEY_STOW_3_Y, Z_PROBE_ALLEN_KEY_STOW_3_Z };
239
+      do_blocking_move_to(stow_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE));
240
+    #endif
241
+    #if defined(Z_PROBE_ALLEN_KEY_STOW_4_X) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Z)
242
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_4_X
243
+        #define Z_PROBE_ALLEN_KEY_STOW_4_X current_position[X_AXIS]
244
+      #endif
245
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_4_Y
246
+        #define Z_PROBE_ALLEN_KEY_STOW_4_Y current_position[Y_AXIS]
247
+      #endif
248
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_4_Z
249
+        #define Z_PROBE_ALLEN_KEY_STOW_4_Z current_position[Z_AXIS]
250
+      #endif
251
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE
252
+        #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0
253
+      #endif
254
+      const float stow_4[] = { Z_PROBE_ALLEN_KEY_STOW_4_X, Z_PROBE_ALLEN_KEY_STOW_4_Y, Z_PROBE_ALLEN_KEY_STOW_4_Z };
255
+      do_blocking_move_to(stow_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE));
256
+    #endif
257
+    #if defined(Z_PROBE_ALLEN_KEY_STOW_5_X) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Z)
258
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_5_X
259
+        #define Z_PROBE_ALLEN_KEY_STOW_5_X current_position[X_AXIS]
260
+      #endif
261
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_5_Y
262
+        #define Z_PROBE_ALLEN_KEY_STOW_5_Y current_position[Y_AXIS]
263
+      #endif
264
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_5_Z
265
+        #define Z_PROBE_ALLEN_KEY_STOW_5_Z current_position[Z_AXIS]
266
+      #endif
267
+      #ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE
268
+        #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0
269
+      #endif
270
+      const float stow_5[] = { Z_PROBE_ALLEN_KEY_STOW_5_X, Z_PROBE_ALLEN_KEY_STOW_5_Y, Z_PROBE_ALLEN_KEY_STOW_5_Z };
271
+      do_blocking_move_to(stow_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE));
272
+    #endif
273
+  }
274
+
275
+#endif
276
+
277
+#if ENABLED(PROBING_FANS_OFF)
278
+
279
+  void fans_pause(const bool p) {
280
+    if (p != fans_paused) {
281
+      fans_paused = p;
282
+      if (p)
283
+        for (uint8_t x = 0; x < FAN_COUNT; x++) {
284
+          paused_fanSpeeds[x] = fanSpeeds[x];
285
+          fanSpeeds[x] = 0;
286
+        }
287
+      else
288
+        for (uint8_t x = 0; x < FAN_COUNT; x++)
289
+          fanSpeeds[x] = paused_fanSpeeds[x];
290
+    }
291
+  }
292
+
293
+#endif // PROBING_FANS_OFF
294
+
295
+#if QUIET_PROBING
296
+  void probing_pause(const bool p) {
297
+    #if ENABLED(PROBING_HEATERS_OFF)
298
+      thermalManager.pause(p);
299
+    #endif
300
+    #if ENABLED(PROBING_FANS_OFF)
301
+      fans_pause(p);
302
+    #endif
303
+    if (p) safe_delay(
304
+      #if DELAY_BEFORE_PROBING > 25
305
+        DELAY_BEFORE_PROBING
306
+      #else
307
+        25
308
+      #endif
309
+    );
310
+  }
311
+#endif // QUIET_PROBING
312
+
313
+#if ENABLED(BLTOUCH)
314
+
315
+  void bltouch_command(const int angle) {
316
+    MOVE_SERVO(Z_ENDSTOP_SERVO_NR, angle);  // Give the BL-Touch the command and wait
317
+    safe_delay(BLTOUCH_DELAY);
318
+  }
319
+
320
+  bool set_bltouch_deployed(const bool deploy) {
321
+    if (deploy && TEST_BLTOUCH()) {      // If BL-Touch says it's triggered
322
+      bltouch_command(BLTOUCH_RESET);    //  try to reset it.
323
+      bltouch_command(BLTOUCH_DEPLOY);   // Also needs to deploy and stow to
324
+      bltouch_command(BLTOUCH_STOW);     //  clear the triggered condition.
325
+      safe_delay(1500);                  // Wait for internal self-test to complete.
326
+                                         //  (Measured completion time was 0.65 seconds
327
+                                         //   after reset, deploy, and stow sequence)
328
+      if (TEST_BLTOUCH()) {              // If it still claims to be triggered...
329
+        SERIAL_ERROR_START();
330
+        SERIAL_ERRORLNPGM(MSG_STOP_BLTOUCH);
331
+        stop();                          // punt!
332
+        return true;
333
+      }
334
+    }
335
+
336
+    bltouch_command(deploy ? BLTOUCH_DEPLOY : BLTOUCH_STOW);
337
+
338
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
339
+      if (DEBUGGING(LEVELING)) {
340
+        SERIAL_ECHOPAIR("set_bltouch_deployed(", deploy);
341
+        SERIAL_CHAR(')');
342
+        SERIAL_EOL();
343
+      }
344
+    #endif
345
+
346
+    return false;
347
+  }
348
+
349
+#endif // BLTOUCH
350
+
351
+// returns false for ok and true for failure
352
+bool set_probe_deployed(const bool deploy) {
353
+
354
+  // Can be extended to servo probes, if needed.
355
+  #if ENABLED(PROBE_IS_TRIGGERED_WHEN_STOWED_TEST)
356
+    #if ENABLED(Z_MIN_PROBE_ENDSTOP)
357
+      #define _TRIGGERED_WHEN_STOWED_TEST (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING)
358
+    #else
359
+      #define _TRIGGERED_WHEN_STOWED_TEST (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING)
360
+    #endif
361
+  #endif
362
+
363
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
364
+    if (DEBUGGING(LEVELING)) {
365
+      DEBUG_POS("set_probe_deployed", current_position);
366
+      SERIAL_ECHOLNPAIR("deploy: ", deploy);
367
+    }
368
+  #endif
369
+
370
+  if (endstops.z_probe_enabled == deploy) return false;
371
+
372
+  // Make room for probe
373
+  do_probe_raise(_Z_CLEARANCE_DEPLOY_PROBE);
374
+
375
+  #if ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY)
376
+    #if ENABLED(Z_PROBE_SLED)
377
+      #define _AUE_ARGS true, false, false
378
+    #else
379
+      #define _AUE_ARGS
380
+    #endif
381
+    if (axis_unhomed_error(_AUE_ARGS)) {
382
+      SERIAL_ERROR_START();
383
+      SERIAL_ERRORLNPGM(MSG_STOP_UNHOMED);
384
+      stop();
385
+      return true;
386
+    }
387
+  #endif
388
+
389
+  const float oldXpos = current_position[X_AXIS],
390
+              oldYpos = current_position[Y_AXIS];
391
+
392
+  #ifdef _TRIGGERED_WHEN_STOWED_TEST
393
+
394
+    // If endstop is already false, the Z probe is deployed
395
+    if (_TRIGGERED_WHEN_STOWED_TEST == deploy) {     // closed after the probe specific actions.
396
+                                                     // Would a goto be less ugly?
397
+      //while (!_TRIGGERED_WHEN_STOWED_TEST) idle(); // would offer the opportunity
398
+                                                     // for a triggered when stowed manual probe.
399
+
400
+      if (!deploy) endstops.enable_z_probe(false); // Switch off triggered when stowed probes early
401
+                                                   // otherwise an Allen-Key probe can't be stowed.
402
+  #endif
403
+
404
+      #if ENABLED(SOLENOID_PROBE)
405
+
406
+        #if HAS_SOLENOID_1
407
+          WRITE(SOL1_PIN, deploy);
408
+        #endif
409
+
410
+      #elif ENABLED(Z_PROBE_SLED)
411
+
412
+        dock_sled(!deploy);
413
+
414
+      #elif HAS_Z_SERVO_ENDSTOP && DISABLED(BLTOUCH)
415
+
416
+        MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[deploy ? 0 : 1]);
417
+
418
+      #elif ENABLED(Z_PROBE_ALLEN_KEY)
419
+
420
+        deploy ? run_deploy_moves_script() : run_stow_moves_script();
421
+
422
+      #endif
423
+
424
+  #ifdef _TRIGGERED_WHEN_STOWED_TEST
425
+    } // _TRIGGERED_WHEN_STOWED_TEST == deploy
426
+
427
+    if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // State hasn't changed?
428
+
429
+      if (IsRunning()) {
430
+        SERIAL_ERROR_START();
431
+        SERIAL_ERRORLNPGM("Z-Probe failed");
432
+        LCD_ALERTMESSAGEPGM("Err: ZPROBE");
433
+      }
434
+      stop();
435
+      return true;
436
+
437
+    } // _TRIGGERED_WHEN_STOWED_TEST == deploy
438
+
439
+  #endif
440
+
441
+  do_blocking_move_to(oldXpos, oldYpos, current_position[Z_AXIS]); // return to position before deploy
442
+  endstops.enable_z_probe(deploy);
443
+  return false;
444
+}
445
+
446
+/**
447
+ * @brief Used by run_z_probe to do a single Z probe move.
448
+ *
449
+ * @param  z        Z destination
450
+ * @param  fr_mm_s  Feedrate in mm/s
451
+ * @return true to indicate an error
452
+ */
453
+static bool do_probe_move(const float z, const float fr_mm_m) {
454
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
455
+    if (DEBUGGING(LEVELING)) DEBUG_POS(">>> do_probe_move", current_position);
456
+  #endif
457
+
458
+  // Deploy BLTouch at the start of any probe
459
+  #if ENABLED(BLTOUCH)
460
+    if (set_bltouch_deployed(true)) return true;
461
+  #endif
462
+
463
+  #if QUIET_PROBING
464
+    probing_pause(true);
465
+  #endif
466
+
467
+  // Move down until probe triggered
468
+  do_blocking_move_to_z(z, MMM_TO_MMS(fr_mm_m));
469
+
470
+  // Check to see if the probe was triggered
471
+  const bool probe_triggered = TEST(Endstops::endstop_hit_bits,
472
+    #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
473
+      Z_MIN
474
+    #else
475
+      Z_MIN_PROBE
476
+    #endif
477
+  );
478
+
479
+  #if QUIET_PROBING
480
+    probing_pause(false);
481
+  #endif
482
+
483
+  // Retract BLTouch immediately after a probe if it was triggered
484
+  #if ENABLED(BLTOUCH)
485
+    if (probe_triggered && set_bltouch_deployed(false)) return true;
486
+  #endif
487
+
488
+  // Clear endstop flags
489
+  endstops.hit_on_purpose();
490
+
491
+  // Get Z where the steppers were interrupted
492
+  set_current_from_steppers_for_axis(Z_AXIS);
493
+
494
+  // Tell the planner where we actually are
495
+  SYNC_PLAN_POSITION_KINEMATIC();
496
+
497
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
498
+    if (DEBUGGING(LEVELING)) DEBUG_POS("<<< do_probe_move", current_position);
499
+  #endif
500
+
501
+  return !probe_triggered;
502
+}
503
+
504
+/**
505
+ * @details Used by probe_pt to do a single Z probe.
506
+ *          Leaves current_position[Z_AXIS] at the height where the probe triggered.
507
+ *
508
+ * @param  short_move Flag for a shorter probe move towards the bed
509
+ * @return The raw Z position where the probe was triggered
510
+ */
511
+static float run_z_probe(const bool short_move=true) {
512
+
513
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
514
+    if (DEBUGGING(LEVELING)) DEBUG_POS(">>> run_z_probe", current_position);
515
+  #endif
516
+
517
+  // Prevent stepper_inactive_time from running out and EXTRUDER_RUNOUT_PREVENT from extruding
518
+  gcode.refresh_cmd_timeout();
519
+
520
+  #if ENABLED(PROBE_DOUBLE_TOUCH)
521
+
522
+    // Do a first probe at the fast speed
523
+    if (do_probe_move(-10, Z_PROBE_SPEED_FAST)) return NAN;
524
+
525
+    #if ENABLED(DEBUG_LEVELING_FEATURE)
526
+      float first_probe_z = current_position[Z_AXIS];
527
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("1st Probe Z:", first_probe_z);
528
+    #endif
529
+
530
+    // move up to make clearance for the probe
531
+    do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST));
532
+
533
+  #else
534
+
535
+    // If the nozzle is above the travel height then
536
+    // move down quickly before doing the slow probe
537
+    float z = Z_CLEARANCE_DEPLOY_PROBE;
538
+    if (zprobe_zoffset < 0) z -= zprobe_zoffset;
539
+
540
+    if (z < current_position[Z_AXIS]) {
541
+
542
+      // If we don't make it to the z position (i.e. the probe triggered), move up to make clearance for the probe
543
+      if (!do_probe_move(z, Z_PROBE_SPEED_FAST))
544
+        do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST));
545
+    }
546
+  #endif
547
+
548
+  // move down slowly to find bed
549
+  if (do_probe_move(-10 + (short_move ? 0 : -(Z_MAX_LENGTH)), Z_PROBE_SPEED_SLOW)) return NAN;
550
+
551
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
552
+    if (DEBUGGING(LEVELING)) DEBUG_POS("<<< run_z_probe", current_position);
553
+  #endif
554
+
555
+  // Debug: compare probe heights
556
+  #if ENABLED(PROBE_DOUBLE_TOUCH) && ENABLED(DEBUG_LEVELING_FEATURE)
557
+    if (DEBUGGING(LEVELING)) {
558
+      SERIAL_ECHOPAIR("2nd Probe Z:", current_position[Z_AXIS]);
559
+      SERIAL_ECHOLNPAIR(" Discrepancy:", first_probe_z - current_position[Z_AXIS]);
560
+    }
561
+  #endif
562
+
563
+  return RAW_CURRENT_POSITION(Z) + zprobe_zoffset
564
+    #if ENABLED(DELTA)
565
+      + home_offset[Z_AXIS] // Account for delta height adjustment
566
+    #endif
567
+  ;
568
+}
569
+
570
+/**
571
+ * - Move to the given XY
572
+ * - Deploy the probe, if not already deployed
573
+ * - Probe the bed, get the Z position
574
+ * - Depending on the 'stow' flag
575
+ *   - Stow the probe, or
576
+ *   - Raise to the BETWEEN height
577
+ * - Return the probed Z position
578
+ */
579
+float probe_pt(const float &lx, const float &ly, const bool stow, const uint8_t verbose_level, const bool printable/*=true*/) {
580
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
581
+    if (DEBUGGING(LEVELING)) {
582
+      SERIAL_ECHOPAIR(">>> probe_pt(", lx);
583
+      SERIAL_ECHOPAIR(", ", ly);
584
+      SERIAL_ECHOPAIR(", ", stow ? "" : "no ");
585
+      SERIAL_ECHOLNPGM("stow)");
586
+      DEBUG_POS("", current_position);
587
+    }
588
+  #endif
589
+
590
+  const float nx = lx - (X_PROBE_OFFSET_FROM_EXTRUDER), ny = ly - (Y_PROBE_OFFSET_FROM_EXTRUDER);
591
+
592
+  if (printable
593
+    ? !position_is_reachable_xy(nx, ny)
594
+    : !position_is_reachable_by_probe_xy(lx, ly)
595
+  ) return NAN;
596
+
597
+
598
+  const float old_feedrate_mm_s = feedrate_mm_s;
599
+
600
+  #if ENABLED(DELTA)
601
+    if (current_position[Z_AXIS] > delta_clip_start_height)
602
+      do_blocking_move_to_z(delta_clip_start_height);
603
+  #endif
604
+
605
+  #if HAS_SOFTWARE_ENDSTOPS
606
+    // Store the status of the soft endstops and disable if we're probing a non-printable location
607
+    static bool enable_soft_endstops = soft_endstops_enabled;
608
+    if (!printable) soft_endstops_enabled = false;
609
+  #endif
610
+
611
+  feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S;
612
+
613
+  // Move the probe to the given XY
614
+  do_blocking_move_to_xy(nx, ny);
615
+
616
+  float measured_z = NAN;
617
+  if (!DEPLOY_PROBE()) {
618
+    measured_z = run_z_probe(printable);
619
+
620
+    if (!stow)
621
+      do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST));
622
+    else
623
+      if (STOW_PROBE()) measured_z = NAN;
624
+  }
625
+
626
+  #if HAS_SOFTWARE_ENDSTOPS
627
+    // Restore the soft endstop status
628
+    soft_endstops_enabled = enable_soft_endstops;
629
+  #endif
630
+
631
+  if (verbose_level > 2) {
632
+    SERIAL_PROTOCOLPGM("Bed X: ");
633
+    SERIAL_PROTOCOL_F(lx, 3);
634
+    SERIAL_PROTOCOLPGM(" Y: ");
635
+    SERIAL_PROTOCOL_F(ly, 3);
636
+    SERIAL_PROTOCOLPGM(" Z: ");
637
+    SERIAL_PROTOCOL_F(measured_z, 3);
638
+    SERIAL_EOL();
639
+  }
640
+
641
+  #if ENABLED(DEBUG_LEVELING_FEATURE)
642
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< probe_pt");
643
+  #endif
644
+
645
+  feedrate_mm_s = old_feedrate_mm_s;
646
+
647
+  if (isnan(measured_z)) {
648
+    LCD_MESSAGEPGM(MSG_ERR_PROBING_FAILED);
649
+    SERIAL_ERROR_START();
650
+    SERIAL_ERRORLNPGM(MSG_ERR_PROBING_FAILED);
651
+  }
652
+
653
+  return measured_z;
654
+}
655
+
656
+void refresh_zprobe_zoffset(const bool no_babystep/*=false*/) {
657
+  static float last_zoffset = NAN;
658
+
659
+  if (!isnan(last_zoffset)) {
660
+
661
+    #if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(BABYSTEP_ZPROBE_OFFSET) || ENABLED(DELTA)
662
+      const float diff = zprobe_zoffset - last_zoffset;
663
+    #endif
664
+
665
+    #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
666
+      // Correct bilinear grid for new probe offset
667
+      if (diff) {
668
+        for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
669
+          for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
670
+            z_values[x][y] -= diff;
671
+      }
672
+      #if ENABLED(ABL_BILINEAR_SUBDIVISION)
673
+        bed_level_virt_interpolate();
674
+      #endif
675
+    #endif
676
+
677
+    #if ENABLED(BABYSTEP_ZPROBE_OFFSET)
678
+      if (!no_babystep && leveling_is_active())
679
+        thermalManager.babystep_axis(Z_AXIS, -LROUND(diff * planner.axis_steps_per_mm[Z_AXIS]));
680
+    #else
681
+      UNUSED(no_babystep);
682
+    #endif
683
+
684
+    #if ENABLED(DELTA) // correct the delta_height
685
+      home_offset[Z_AXIS] -= diff;
686
+    #endif
687
+  }
688
+
689
+  last_zoffset = zprobe_zoffset;
690
+}
691
+
692
+#if HAS_Z_SERVO_ENDSTOP
693
+
694
+  void servo_probe_init() {
695
+    /**
696
+     * Set position of Z Servo Endstop
697
+     *
698
+     * The servo might be deployed and positioned too low to stow
699
+     * when starting up the machine or rebooting the board.
700
+     * There's no way to know where the nozzle is positioned until
701
+     * homing has been done - no homing with z-probe without init!
702
+     *
703
+     */
704
+    STOW_Z_SERVO();
705
+  }
706
+
707
+#endif // HAS_Z_SERVO_ENDSTOP
708
+
709
+#endif // HAS_BED_PROBE

+ 69
- 0
Marlin/src/module/probe.h View File

@@ -0,0 +1,69 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * probe.h - Move, deploy, enable, etc.
25
+ */
26
+
27
+#ifndef PROBE_H
28
+#define PROBE_H
29
+
30
+#include "../inc/MarlinConfig.h"
31
+
32
+bool set_probe_deployed(const bool deploy);
33
+float probe_pt(const float &lx, const float &ly, const bool, const uint8_t, const bool printable=true);
34
+
35
+#if HAS_BED_PROBE
36
+  extern float zprobe_zoffset;
37
+  void refresh_zprobe_zoffset(const bool no_babystep=false);
38
+  #define DEPLOY_PROBE() set_probe_deployed(true)
39
+  #define STOW_PROBE() set_probe_deployed(false)
40
+#else
41
+  #define DEPLOY_PROBE()
42
+  #define STOW_PROBE()
43
+#endif
44
+
45
+#if HAS_Z_SERVO_ENDSTOP
46
+  extern const int z_servo_angle[2];
47
+  void servo_probe_init();
48
+#endif
49
+
50
+#if QUIET_PROBING
51
+  void probing_pause(const bool p);
52
+#endif
53
+
54
+#if ENABLED(PROBING_FANS_OFF)
55
+  void fans_pause(const bool p);
56
+#endif
57
+
58
+#if ENABLED(BLTOUCH)
59
+  void bltouch_command(int angle);
60
+  bool set_bltouch_deployed(const bool deploy);
61
+  FORCE_INLINE void bltouch_init() {
62
+    // Make sure any BLTouch error condition is cleared
63
+    bltouch_command(BLTOUCH_RESET);
64
+    set_bltouch_deployed(true);
65
+    set_bltouch_deployed(false);
66
+  }
67
+#endif
68
+
69
+#endif // PROBE_H

+ 155
- 0
Marlin/src/module/scara.cpp View File

@@ -0,0 +1,155 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * scara.cpp
25
+ */
26
+
27
+#include "../inc/MarlinConfig.h"
28
+
29
+#if IS_SCARA
30
+
31
+#include "scara.h"
32
+#include "motion.h"
33
+#include "stepper.h"
34
+
35
+float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND;
36
+
37
+void scara_set_axis_is_at_home(const AxisEnum axis) {
38
+  if (axis == Z_AXIS)
39
+    current_position[Z_AXIS] = LOGICAL_POSITION(Z_HOME_POS, Z_AXIS);
40
+  else {
41
+
42
+    /**
43
+     * SCARA homes XY at the same time
44
+     */
45
+    float homeposition[XYZ];
46
+    LOOP_XYZ(i) homeposition[i] = LOGICAL_POSITION(base_home_pos((AxisEnum)i), i);
47
+
48
+    // SERIAL_ECHOPAIR("homeposition X:", homeposition[X_AXIS]);
49
+    // SERIAL_ECHOLNPAIR(" Y:", homeposition[Y_AXIS]);
50
+
51
+    /**
52
+     * Get Home position SCARA arm angles using inverse kinematics,
53
+     * and calculate homing offset using forward kinematics
54
+     */
55
+    inverse_kinematics(homeposition);
56
+    forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]);
57
+
58
+    // SERIAL_ECHOPAIR("Cartesian X:", cartes[X_AXIS]);
59
+    // SERIAL_ECHOLNPAIR(" Y:", cartes[Y_AXIS]);
60
+
61
+    current_position[axis] = LOGICAL_POSITION(cartes[axis], axis);
62
+
63
+    /**
64
+     * SCARA home positions are based on configuration since the actual
65
+     * limits are determined by the inverse kinematic transform.
66
+     */
67
+    soft_endstop_min[axis] = base_min_pos(axis); // + (cartes[axis] - base_home_pos(axis));
68
+    soft_endstop_max[axis] = base_max_pos(axis); // + (cartes[axis] - base_home_pos(axis));
69
+  }
70
+}
71
+
72
+/**
73
+ * Morgan SCARA Forward Kinematics. Results in cartes[].
74
+ * Maths and first version by QHARLEY.
75
+ * Integrated into Marlin and slightly restructured by Joachim Cerny.
76
+ */
77
+void forward_kinematics_SCARA(const float &a, const float &b) {
78
+
79
+  const float a_sin = sin(RADIANS(a)) * L1,
80
+              a_cos = cos(RADIANS(a)) * L1,
81
+              b_sin = sin(RADIANS(b)) * L2,
82
+              b_cos = cos(RADIANS(b)) * L2;
83
+
84
+  cartes[X_AXIS] = a_cos + b_cos + SCARA_OFFSET_X;  //theta
85
+  cartes[Y_AXIS] = a_sin + b_sin + SCARA_OFFSET_Y;  //theta+phi
86
+
87
+  /*
88
+    SERIAL_ECHOPAIR("SCARA FK Angle a=", a);
89
+    SERIAL_ECHOPAIR(" b=", b);
90
+    SERIAL_ECHOPAIR(" a_sin=", a_sin);
91
+    SERIAL_ECHOPAIR(" a_cos=", a_cos);
92
+    SERIAL_ECHOPAIR(" b_sin=", b_sin);
93
+    SERIAL_ECHOLNPAIR(" b_cos=", b_cos);
94
+    SERIAL_ECHOPAIR(" cartes[X_AXIS]=", cartes[X_AXIS]);
95
+    SERIAL_ECHOLNPAIR(" cartes[Y_AXIS]=", cartes[Y_AXIS]);
96
+  //*/
97
+}
98
+
99
+/**
100
+ * Morgan SCARA Inverse Kinematics. Results in delta[].
101
+ *
102
+ * See http://forums.reprap.org/read.php?185,283327
103
+ *
104
+ * Maths and first version by QHARLEY.
105
+ * Integrated into Marlin and slightly restructured by Joachim Cerny.
106
+ */
107
+void inverse_kinematics(const float logical[XYZ]) {
108
+
109
+  static float C2, S2, SK1, SK2, THETA, PSI;
110
+
111
+  float sx = RAW_X_POSITION(logical[X_AXIS]) - SCARA_OFFSET_X,  // Translate SCARA to standard X Y
112
+        sy = RAW_Y_POSITION(logical[Y_AXIS]) - SCARA_OFFSET_Y;  // With scaling factor.
113
+
114
+  if (L1 == L2)
115
+    C2 = HYPOT2(sx, sy) / L1_2_2 - 1;
116
+  else
117
+    C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2);
118
+
119
+  S2 = SQRT(1 - sq(C2));
120
+
121
+  // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
122
+  SK1 = L1 + L2 * C2;
123
+
124
+  // Rotated Arm2 gives the distance from Arm1 to Arm2
125
+  SK2 = L2 * S2;
126
+
127
+  // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
128
+  THETA = ATAN2(SK1, SK2) - ATAN2(sx, sy);
129
+
130
+  // Angle of Arm2
131
+  PSI = ATAN2(S2, C2);
132
+
133
+  delta[A_AXIS] = DEGREES(THETA);        // theta is support arm angle
134
+  delta[B_AXIS] = DEGREES(THETA + PSI);  // equal to sub arm angle (inverted motor)
135
+  delta[C_AXIS] = logical[Z_AXIS];
136
+
137
+  /*
138
+    DEBUG_POS("SCARA IK", logical);
139
+    DEBUG_POS("SCARA IK", delta);
140
+    SERIAL_ECHOPAIR("  SCARA (x,y) ", sx);
141
+    SERIAL_ECHOPAIR(",", sy);
142
+    SERIAL_ECHOPAIR(" C2=", C2);
143
+    SERIAL_ECHOPAIR(" S2=", S2);
144
+    SERIAL_ECHOPAIR(" Theta=", THETA);
145
+    SERIAL_ECHOLNPAIR(" Phi=", PHI);
146
+  //*/
147
+}
148
+
149
+void scara_report_positions() {
150
+  SERIAL_PROTOCOLPAIR("SCARA Theta:", stepper.get_axis_position_degrees(A_AXIS));
151
+  SERIAL_PROTOCOLLNPAIR("   Psi+Theta:", stepper.get_axis_position_degrees(B_AXIS));
152
+  SERIAL_EOL();
153
+}
154
+
155
+#endif // IS_SCARA

+ 46
- 0
Marlin/src/module/scara.h View File

@@ -0,0 +1,46 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * scara.h - SCARA-specific functions
25
+ */
26
+
27
+#ifndef __SCARA_H__
28
+#define __SCARA_H__
29
+
30
+#include "../core/macros.h"
31
+
32
+extern float delta_segments_per_second;
33
+
34
+// Float constants for SCARA calculations
35
+float constexpr L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2,
36
+                L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2,
37
+                L2_2 = sq(float(L2));
38
+
39
+void scara_set_axis_is_at_home(const AxisEnum axis);
40
+
41
+void inverse_kinematics(const float logical[XYZ]);
42
+void forward_kinematics_SCARA(const float &a, const float &b);
43
+
44
+void scara_report_positions();
45
+
46
+#endif // __SCARA_H__

+ 1
- 0
Marlin/src/module/stepper.cpp View File

@@ -52,6 +52,7 @@
52 52
 
53 53
 #include "endstops.h"
54 54
 #include "planner.h"
55
+#include "motion.h"
55 56
 
56 57
 #include "../Marlin.h"
57 58
 #include "../module/temperature.h"

Loading…
Cancel
Save