My Marlin configs for Fabrikator Mini and CTC i3 Pro B
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405
  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. #ifndef UNIFIED_BED_LEVELING_H
  23. #define UNIFIED_BED_LEVELING_H
  24. #include "MarlinConfig.h"
  25. #if ENABLED(AUTO_BED_LEVELING_UBL)
  26. #include "Marlin.h"
  27. #include "planner.h"
  28. #include "math.h"
  29. #include "vector_3.h"
  30. #include "configuration_store.h"
  31. #define UBL_VERSION "1.01"
  32. #define UBL_OK false
  33. #define UBL_ERR true
  34. #define USE_NOZZLE_AS_REFERENCE 0
  35. #define USE_PROBE_AS_REFERENCE 1
  36. typedef struct {
  37. int8_t x_index, y_index;
  38. float distance; // When populated, the distance from the search location
  39. } mesh_index_pair;
  40. // ubl.cpp
  41. void bit_clear(uint16_t bits[16], const uint8_t x, const uint8_t y);
  42. void bit_set(uint16_t bits[16], const uint8_t x, const uint8_t y);
  43. bool is_bit_set(uint16_t bits[16], const uint8_t x, const uint8_t y);
  44. // ubl_motion.cpp
  45. void debug_current_and_destination(const char * const title);
  46. // ubl_G29.cpp
  47. enum MeshPointType { INVALID, REAL, SET_IN_BITMAP };
  48. // External references
  49. char *ftostr43sign(const float&, char);
  50. bool ubl_lcd_clicked();
  51. void home_all_axes();
  52. extern uint8_t ubl_cnt;
  53. ///////////////////////////////////////////////////////////////////////////////////////////////////////
  54. #if ENABLED(ULTRA_LCD)
  55. extern char lcd_status_message[];
  56. void lcd_quick_feedback();
  57. #endif
  58. #define MESH_X_DIST (float(MESH_MAX_X - (MESH_MIN_X)) / float(GRID_MAX_POINTS_X - 1))
  59. #define MESH_Y_DIST (float(MESH_MAX_Y - (MESH_MIN_Y)) / float(GRID_MAX_POINTS_Y - 1))
  60. class unified_bed_leveling {
  61. private:
  62. static int g29_verbose_level,
  63. g29_phase_value,
  64. g29_repetition_cnt,
  65. g29_storage_slot,
  66. g29_map_type;
  67. static bool g29_c_flag, g29_x_flag, g29_y_flag;
  68. static float g29_x_pos, g29_y_pos,
  69. g29_card_thickness,
  70. g29_constant;
  71. #if HAS_BED_PROBE
  72. static int g29_grid_size;
  73. #endif
  74. #if ENABLED(UBL_G26_MESH_VALIDATION)
  75. static float g26_extrusion_multiplier,
  76. g26_retraction_multiplier,
  77. g26_nozzle,
  78. g26_filament_diameter,
  79. g26_prime_length,
  80. g26_x_pos, g26_y_pos,
  81. g26_ooze_amount,
  82. g26_layer_height;
  83. static int16_t g26_bed_temp,
  84. g26_hotend_temp,
  85. g26_repeats;
  86. static int8_t g26_prime_flag;
  87. static bool g26_continue_with_closest, g26_keep_heaters_on;
  88. #endif
  89. static float measure_point_with_encoder();
  90. static float measure_business_card_thickness(float);
  91. static bool g29_parameter_parsing();
  92. static void find_mean_mesh_height();
  93. static void shift_mesh_height();
  94. static void probe_entire_mesh(const float &rx, const float &ry, const bool do_ubl_mesh_map, const bool stow_probe, bool do_furthest);
  95. static void manually_probe_remaining_mesh(const float&, const float&, const float&, const float&, const bool);
  96. static void tilt_mesh_based_on_3pts(const float &z1, const float &z2, const float &z3);
  97. static void tilt_mesh_based_on_probed_grid(const bool do_ubl_mesh_map);
  98. static void g29_what_command();
  99. static void g29_eeprom_dump();
  100. static void g29_compare_current_mesh_to_stored_mesh();
  101. static void fine_tune_mesh(const float &rx, const float &ry, const bool do_ubl_mesh_map);
  102. static bool smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir);
  103. static void smart_fill_mesh();
  104. #if ENABLED(UBL_G26_MESH_VALIDATION)
  105. static bool exit_from_g26();
  106. static bool parse_G26_parameters();
  107. static void G26_line_to_destination(const float &feed_rate);
  108. static mesh_index_pair find_closest_circle_to_print(const float&, const float&);
  109. static bool look_for_lines_to_connect();
  110. static bool turn_on_heaters();
  111. static bool prime_nozzle();
  112. static void retract_filament(const float where[XYZE]);
  113. static void recover_filament(const float where[XYZE]);
  114. static void print_line_from_here_to_there(const float&, const float&, const float&, const float&, const float&, const float&);
  115. static void move_to(const float&, const float&, const float&, const float&);
  116. inline static void move_to(const float where[XYZE], const float &de) { move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], de); }
  117. #endif
  118. public:
  119. static void echo_name();
  120. static void report_state();
  121. static void save_ubl_active_state_and_disable();
  122. static void restore_ubl_active_state_and_leave();
  123. static void display_map(const int);
  124. static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const float&, const float&, const bool, uint16_t[16]);
  125. static mesh_index_pair find_furthest_invalid_mesh_point();
  126. static void reset();
  127. static void invalidate();
  128. static void set_all_mesh_points_to_value(const float);
  129. static bool sanity_check();
  130. static void G29() _O0; // O0 for no optimization
  131. static void smart_fill_wlsf(const float &) _O2; // O2 gives smaller code than Os on A2560
  132. #if ENABLED(UBL_G26_MESH_VALIDATION)
  133. static void G26();
  134. #endif
  135. static int8_t storage_slot;
  136. static float z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
  137. // 15 is the maximum nubmer of grid points supported + 1 safety margin for now,
  138. // until determinism prevails
  139. constexpr static float _mesh_index_to_xpos[16] PROGMEM = {
  140. MESH_MIN_X + 0 * (MESH_X_DIST), MESH_MIN_X + 1 * (MESH_X_DIST),
  141. MESH_MIN_X + 2 * (MESH_X_DIST), MESH_MIN_X + 3 * (MESH_X_DIST),
  142. MESH_MIN_X + 4 * (MESH_X_DIST), MESH_MIN_X + 5 * (MESH_X_DIST),
  143. MESH_MIN_X + 6 * (MESH_X_DIST), MESH_MIN_X + 7 * (MESH_X_DIST),
  144. MESH_MIN_X + 8 * (MESH_X_DIST), MESH_MIN_X + 9 * (MESH_X_DIST),
  145. MESH_MIN_X + 10 * (MESH_X_DIST), MESH_MIN_X + 11 * (MESH_X_DIST),
  146. MESH_MIN_X + 12 * (MESH_X_DIST), MESH_MIN_X + 13 * (MESH_X_DIST),
  147. MESH_MIN_X + 14 * (MESH_X_DIST), MESH_MIN_X + 15 * (MESH_X_DIST)
  148. };
  149. constexpr static float _mesh_index_to_ypos[16] PROGMEM = {
  150. MESH_MIN_Y + 0 * (MESH_Y_DIST), MESH_MIN_Y + 1 * (MESH_Y_DIST),
  151. MESH_MIN_Y + 2 * (MESH_Y_DIST), MESH_MIN_Y + 3 * (MESH_Y_DIST),
  152. MESH_MIN_Y + 4 * (MESH_Y_DIST), MESH_MIN_Y + 5 * (MESH_Y_DIST),
  153. MESH_MIN_Y + 6 * (MESH_Y_DIST), MESH_MIN_Y + 7 * (MESH_Y_DIST),
  154. MESH_MIN_Y + 8 * (MESH_Y_DIST), MESH_MIN_Y + 9 * (MESH_Y_DIST),
  155. MESH_MIN_Y + 10 * (MESH_Y_DIST), MESH_MIN_Y + 11 * (MESH_Y_DIST),
  156. MESH_MIN_Y + 12 * (MESH_Y_DIST), MESH_MIN_Y + 13 * (MESH_Y_DIST),
  157. MESH_MIN_Y + 14 * (MESH_Y_DIST), MESH_MIN_Y + 15 * (MESH_Y_DIST)
  158. };
  159. static bool g26_debug_flag, has_control_of_lcd_panel;
  160. #if ENABLED(ULTIPANEL)
  161. static bool lcd_map_control;
  162. #endif
  163. static volatile int encoder_diff; // Volatile because it's changed at interrupt time.
  164. unified_bed_leveling();
  165. FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; }
  166. static int8_t get_cell_index_x(const float &x) {
  167. const int8_t cx = (x - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST));
  168. return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1); // -1 is appropriate if we want all movement to the X_MAX
  169. } // position. But with this defined this way, it is possible
  170. // to extrapolate off of this point even further out. Probably
  171. // that is OK because something else should be keeping that from
  172. // happening and should not be worried about at this level.
  173. static int8_t get_cell_index_y(const float &y) {
  174. const int8_t cy = (y - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST));
  175. return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1); // -1 is appropriate if we want all movement to the Y_MAX
  176. } // position. But with this defined this way, it is possible
  177. // to extrapolate off of this point even further out. Probably
  178. // that is OK because something else should be keeping that from
  179. // happening and should not be worried about at this level.
  180. static int8_t find_closest_x_index(const float &x) {
  181. const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * (1.0 / (MESH_X_DIST));
  182. return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1;
  183. }
  184. static int8_t find_closest_y_index(const float &y) {
  185. const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * (1.0 / (MESH_Y_DIST));
  186. return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1;
  187. }
  188. /**
  189. * z2 --|
  190. * z0 | |
  191. * | | + (z2-z1)
  192. * z1 | | |
  193. * ---+-------------+--------+-- --|
  194. * a1 a0 a2
  195. * |<---delta_a---------->|
  196. *
  197. * calc_z0 is the basis for all the Mesh Based correction. It is used to
  198. * find the expected Z Height at a position between two known Z-Height locations.
  199. *
  200. * It is fairly expensive with its 4 floating point additions and 2 floating point
  201. * multiplications.
  202. */
  203. FORCE_INLINE static float calc_z0(const float &a0, const float &a1, const float &z1, const float &a2, const float &z2) {
  204. return z1 + (z2 - z1) * (a0 - a1) / (a2 - a1);
  205. }
  206. /**
  207. * z_correction_for_x_on_horizontal_mesh_line is an optimization for
  208. * the case where the printer is making a vertical line that only crosses horizontal mesh lines.
  209. */
  210. inline static float z_correction_for_x_on_horizontal_mesh_line(const float &rx0, const int x1_i, const int yi) {
  211. if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 2) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) {
  212. #if ENABLED(DEBUG_LEVELING_FEATURE)
  213. if (DEBUGGING(LEVELING)) {
  214. serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") );
  215. SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0);
  216. SERIAL_ECHOPAIR(",x1_i=", x1_i);
  217. SERIAL_ECHOPAIR(",yi=", yi);
  218. SERIAL_CHAR(')');
  219. SERIAL_EOL();
  220. }
  221. #endif
  222. return NAN;
  223. }
  224. const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * (1.0 / (MESH_X_DIST)),
  225. z1 = z_values[x1_i][yi];
  226. return z1 + xratio * (z_values[x1_i + 1][yi] - z1);
  227. }
  228. //
  229. // See comments above for z_correction_for_x_on_horizontal_mesh_line
  230. //
  231. inline static float z_correction_for_y_on_vertical_mesh_line(const float &ry0, const int xi, const int y1_i) {
  232. if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 2)) {
  233. #if ENABLED(DEBUG_LEVELING_FEATURE)
  234. if (DEBUGGING(LEVELING)) {
  235. serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") );
  236. SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0);
  237. SERIAL_ECHOPAIR(", xi=", xi);
  238. SERIAL_ECHOPAIR(", y1_i=", y1_i);
  239. SERIAL_CHAR(')');
  240. SERIAL_EOL();
  241. }
  242. #endif
  243. return NAN;
  244. }
  245. const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * (1.0 / (MESH_Y_DIST)),
  246. z1 = z_values[xi][y1_i];
  247. return z1 + yratio * (z_values[xi][y1_i + 1] - z1);
  248. }
  249. /**
  250. * This is the generic Z-Correction. It works anywhere within a Mesh Cell. It first
  251. * does a linear interpolation along both of the bounding X-Mesh-Lines to find the
  252. * Z-Height at both ends. Then it does a linear interpolation of these heights based
  253. * on the Y position within the cell.
  254. */
  255. static float get_z_correction(const float &rx0, const float &ry0) {
  256. const int8_t cx = get_cell_index_x(rx0),
  257. cy = get_cell_index_y(ry0);
  258. if (!WITHIN(cx, 0, GRID_MAX_POINTS_X - 2) || !WITHIN(cy, 0, GRID_MAX_POINTS_Y - 2)) {
  259. SERIAL_ECHOPAIR("? in get_z_correction(rx0=", rx0);
  260. SERIAL_ECHOPAIR(", ry0=", ry0);
  261. SERIAL_CHAR(')');
  262. SERIAL_EOL();
  263. #if ENABLED(ULTRA_LCD)
  264. strcpy(lcd_status_message, "get_z_correction() indexes out of range.");
  265. lcd_quick_feedback();
  266. #endif
  267. return NAN;
  268. }
  269. const float z1 = calc_z0(rx0,
  270. mesh_index_to_xpos(cx), z_values[cx][cy],
  271. mesh_index_to_xpos(cx + 1), z_values[cx + 1][cy]);
  272. const float z2 = calc_z0(rx0,
  273. mesh_index_to_xpos(cx), z_values[cx][cy + 1],
  274. mesh_index_to_xpos(cx + 1), z_values[cx + 1][cy + 1]);
  275. float z0 = calc_z0(ry0,
  276. mesh_index_to_ypos(cy), z1,
  277. mesh_index_to_ypos(cy + 1), z2);
  278. #if ENABLED(DEBUG_LEVELING_FEATURE)
  279. if (DEBUGGING(MESH_ADJUST)) {
  280. SERIAL_ECHOPAIR(" raw get_z_correction(", rx0);
  281. SERIAL_CHAR(',');
  282. SERIAL_ECHO(ry0);
  283. SERIAL_ECHOPGM(") = ");
  284. SERIAL_ECHO_F(z0, 6);
  285. }
  286. #endif
  287. #if ENABLED(DEBUG_LEVELING_FEATURE)
  288. if (DEBUGGING(MESH_ADJUST)) {
  289. SERIAL_ECHOPGM(" >>>---> ");
  290. SERIAL_ECHO_F(z0, 6);
  291. SERIAL_EOL();
  292. }
  293. #endif
  294. if (isnan(z0)) { // if part of the Mesh is undefined, it will show up as NAN
  295. z0 = 0.0; // in ubl.z_values[][] and propagate through the
  296. // calculations. If our correction is NAN, we throw it out
  297. // because part of the Mesh is undefined and we don't have the
  298. // information we need to complete the height correction.
  299. #if ENABLED(DEBUG_LEVELING_FEATURE)
  300. if (DEBUGGING(MESH_ADJUST)) {
  301. SERIAL_ECHOPAIR("??? Yikes! NAN in get_z_correction(", rx0);
  302. SERIAL_CHAR(',');
  303. SERIAL_ECHO(ry0);
  304. SERIAL_CHAR(')');
  305. SERIAL_EOL();
  306. }
  307. #endif
  308. }
  309. return z0;
  310. }
  311. FORCE_INLINE static float mesh_index_to_xpos(const uint8_t i) {
  312. return i < GRID_MAX_POINTS_X ? pgm_read_float(&_mesh_index_to_xpos[i]) : MESH_MIN_X + i * (MESH_X_DIST);
  313. }
  314. FORCE_INLINE static float mesh_index_to_ypos(const uint8_t i) {
  315. return i < GRID_MAX_POINTS_Y ? pgm_read_float(&_mesh_index_to_ypos[i]) : MESH_MIN_Y + i * (MESH_Y_DIST);
  316. }
  317. static bool prepare_segmented_line_to(const float rtarget[XYZE], const float &feedrate);
  318. static void line_to_destination_cartesian(const float &fr, uint8_t e);
  319. #define _CMPZ(a,b) (z_values[a][b] == z_values[a][b+1])
  320. #define CMPZ(a) (_CMPZ(a, 0) && _CMPZ(a, 1))
  321. #define ZZER(a) (z_values[a][0] == 0)
  322. FORCE_INLINE bool mesh_is_valid() {
  323. return !(
  324. ( CMPZ(0) && CMPZ(1) && CMPZ(2) // adjacent z values all equal?
  325. && ZZER(0) && ZZER(1) && ZZER(2) // all zero at the edge?
  326. )
  327. || isnan(z_values[0][0])
  328. );
  329. }
  330. }; // class unified_bed_leveling
  331. extern unified_bed_leveling ubl;
  332. #if ENABLED(UBL_G26_MESH_VALIDATION)
  333. FORCE_INLINE void gcode_G26() { ubl.G26(); }
  334. #endif
  335. FORCE_INLINE void gcode_G29() { ubl.G29(); }
  336. #endif // AUTO_BED_LEVELING_UBL
  337. #endif // UNIFIED_BED_LEVELING_H