From 6292d9e8155fd7372fa2019881c270911763dd34 Mon Sep 17 00:00:00 2001 From: Richard Wackerbarth Date: Wed, 5 Aug 2015 07:12:26 -0500 Subject: [PATCH 1/3] Rename ENABLE_AUTO_BED_LEVELING MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit With the introduction of the #if ENABLED(…) reads better than --- Marlin/Conditionals.h | 4 +- Marlin/Configuration.h | 11 ++-- Marlin/Marlin.h | 4 +- Marlin/Marlin_main.cpp | 54 +++++++++---------- Marlin/SanityCheck.h | 14 ++--- Marlin/configuration_store.cpp | 8 +-- Marlin/configurator/config/Configuration.h | 11 ++-- .../Felix/Configuration.h | 11 ++-- .../Felix/Configuration_DUAL.h | 12 +++-- .../Hephestos/Configuration.h | 12 +++-- .../K8200/Configuration.h | 11 ++-- .../RepRapWorld/Megatronics/Configuration.h | 12 +++-- .../RigidBot/Configuration.h | 11 ++-- .../SCARA/Configuration.h | 11 ++-- .../WITBOX/Configuration.h | 11 ++-- .../adafruit/ST7565/Configuration.h | 12 +++-- .../delta/biv2.5/Configuration.h | 11 ++-- .../delta/generic/Configuration.h | 12 +++-- .../delta/kossel_mini/Configuration.h | 12 +++-- .../delta/kossel_pro/Configuration.h | 12 +++-- .../makibox/Configuration.h | 11 ++-- .../tvrrug/Round2/Configuration.h | 12 +++-- Marlin/planner.cpp | 20 +++---- Marlin/planner.h | 8 +-- Marlin/ultralcd.cpp | 4 +- Marlin/vector_3.cpp | 4 +- Marlin/vector_3.h | 4 +- 27 files changed, 173 insertions(+), 146 deletions(-) diff --git a/Marlin/Conditionals.h b/Marlin/Conditionals.h index 665ff45b3..29659feb8 100644 --- a/Marlin/Conditionals.h +++ b/Marlin/Conditionals.h @@ -279,7 +279,7 @@ /** * Auto Bed Leveling */ - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) // Boundaries for probing based on set limits #define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER)) #define MAX_PROBE_X (min(X_MAX_POS, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER)) @@ -287,7 +287,7 @@ #define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER)) #endif - #define SERVO_LEVELING (defined(ENABLE_AUTO_BED_LEVELING) && defined(Z_ENDSTOP_SERVO_NR)) + #define SERVO_LEVELING (defined(AUTO_BED_LEVELING_FEATURE) && defined(Z_ENDSTOP_SERVO_NR)) /** * Sled Options diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 772683877..bc972625b 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -442,10 +442,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l // @section bedlevel -//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line). -#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z probe repeatability test will be included if auto bed leveling is enabled. +//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line) +//#define DEBUG_LEVELING_FEATURE +#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled. -#if ENABLED(ENABLE_AUTO_BED_LEVELING) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) // There are 2 different ways to specify probing locations: // @@ -557,7 +558,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l // //#define Z_MIN_PROBE_ENDSTOP -#endif // ENABLE_AUTO_BED_LEVELING +#endif // AUTO_BED_LEVELING_FEATURE // @section homing @@ -608,7 +609,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l // Custom M code points #define CUSTOM_M_CODES #if ENABLED(CUSTOM_M_CODES) - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) #define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851 #define Z_PROBE_OFFSET_RANGE_MIN -20 #define Z_PROBE_OFFSET_RANGE_MAX 20 diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 4c6ef0adb..33487c869 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -268,7 +268,7 @@ extern bool axis_known_position[3]; // axis[n].is_known extern float delta_diagonal_rod; extern float delta_segments_per_second; void recalc_delta_settings(float radius, float diagonal_rod); - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) extern int delta_grid_spacing[2]; void adjust_delta(float cartesian[3]); #endif @@ -282,7 +282,7 @@ extern bool axis_known_position[3]; // axis[n].is_known extern float z_endstop_adj; #endif -#if ENABLED(ENABLE_AUTO_BED_LEVELING) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) extern float zprobe_zoffset; #endif diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 88c5bfc8d..ea4b2fd21 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -29,12 +29,12 @@ #include "Marlin.h" -#if ENABLED(ENABLE_AUTO_BED_LEVELING) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) #include "vector_3.h" #if ENABLED(AUTO_BED_LEVELING_GRID) #include "qr_solve.h" #endif -#endif // ENABLE_AUTO_BED_LEVELING +#endif // AUTO_BED_LEVELING_FEATURE #if ENABLED(MESH_BED_LEVELING) #include "mesh_bed_leveling.h" @@ -288,7 +288,7 @@ static uint8_t target_extruder; bool no_wait_for_cooling = true; bool target_direction; -#if ENABLED(ENABLE_AUTO_BED_LEVELING) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) int xy_travel_speed = XY_TRAVEL_SPEED; float zprobe_zoffset = Z_PROBE_OFFSET_FROM_EXTRUDER; #endif @@ -366,7 +366,7 @@ bool target_direction; float delta_diagonal_rod = DELTA_DIAGONAL_ROD; float delta_diagonal_rod_2 = sq(delta_diagonal_rod); float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) int delta_grid_spacing[2] = { 0, 0 }; float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS]; #endif @@ -1095,7 +1095,7 @@ static void set_axis_is_at_home(AxisEnum axis) { min_pos[axis] = base_min_pos(axis) + home_offset[axis]; max_pos[axis] = base_max_pos(axis) + home_offset[axis]; - #if ENABLED(ENABLE_AUTO_BED_LEVELING) && Z_HOME_DIR < 0 + #if ENABLED(AUTO_BED_LEVELING_FEATURE) && Z_HOME_DIR < 0 if (axis == Z_AXIS) current_position[Z_AXIS] -= zprobe_zoffset; #endif } @@ -1146,7 +1146,7 @@ static void setup_for_endstop_move() { enable_endstops(true); } -#if ENABLED(ENABLE_AUTO_BED_LEVELING) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) #if ENABLED(DELTA) /** @@ -1604,7 +1604,7 @@ static void setup_for_endstop_move() { #endif -#endif // ENABLE_AUTO_BED_LEVELING +#endif // AUTO_BED_LEVELING_FEATURE #if ENABLED(Z_PROBE_SLED) @@ -2000,7 +2000,7 @@ inline void gcode_G28() { st_synchronize(); // For auto bed leveling, clear the level matrix - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) plan_bed_level_matrix.set_to_identity(); #if ENABLED(DELTA) reset_bed_level(); @@ -2395,7 +2395,7 @@ inline void gcode_G28() { } // switch(state) } -#elif ENABLED(ENABLE_AUTO_BED_LEVELING) +#elif ENABLED(AUTO_BED_LEVELING_FEATURE) void out_of_range_error(const char *p_edge) { SERIAL_PROTOCOLPGM("?Probe "); @@ -2839,7 +2839,7 @@ inline void gcode_G28() { #endif //!Z_PROBE_SLED -#endif //ENABLE_AUTO_BED_LEVELING +#endif //AUTO_BED_LEVELING_FEATURE /** * G92: Set current position to given X Y Z E @@ -3116,7 +3116,7 @@ inline void gcode_M42() { } // code_seen('S') } -#if ENABLED(ENABLE_AUTO_BED_LEVELING) && ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) && ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) // This is redundant since the SanityCheck.h already checks for a valid Z_MIN_PROBE_PIN, but here for clarity. #if ENABLED(Z_MIN_PROBE_ENDSTOP) @@ -3366,7 +3366,7 @@ inline void gcode_M42() { SERIAL_EOL; SERIAL_EOL; } -#endif // ENABLE_AUTO_BED_LEVELING && Z_MIN_PROBE_REPEATABILITY_TEST +#endif // AUTO_BED_LEVELING_FEATURE && Z_MIN_PROBE_REPEATABILITY_TEST /** * M104: Set hot end temperature @@ -4585,7 +4585,7 @@ inline void gcode_M303() { */ inline void gcode_M400() { st_synchronize(); } -#if ENABLED(ENABLE_AUTO_BED_LEVELING) && DISABLED(Z_PROBE_SLED) && (HAS_SERVO_ENDSTOPS || ENABLED(Z_PROBE_ALLEN_KEY)) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) && DISABLED(Z_PROBE_SLED) && (HAS_SERVO_ENDSTOPS || ENABLED(Z_PROBE_ALLEN_KEY)) /** * M401: Engage Z Servo endstop if available @@ -4607,7 +4607,7 @@ inline void gcode_M400() { st_synchronize(); } stow_z_probe(false); } -#endif // ENABLE_AUTO_BED_LEVELING && (HAS_SERVO_ENDSTOPS || Z_PROBE_ALLEN_KEY) && !Z_PROBE_SLED +#endif // AUTO_BED_LEVELING_FEATURE && (HAS_SERVO_ENDSTOPS || Z_PROBE_ALLEN_KEY) && !Z_PROBE_SLED #if ENABLED(FILAMENT_SENSOR) @@ -5282,13 +5282,13 @@ void process_next_command() { gcode_G28(); break; - #if ENABLED(ENABLE_AUTO_BED_LEVELING) || ENABLED(MESH_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING) case 29: // G29 Detailed Z probe, probes the bed at 3 or more points. gcode_G29(); break; #endif - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) #if DISABLED(Z_PROBE_SLED) @@ -5305,7 +5305,7 @@ void process_next_command() { #endif // Z_PROBE_SLED - #endif // ENABLE_AUTO_BED_LEVELING + #endif // AUTO_BED_LEVELING_FEATURE case 90: // G90 relative_mode = false; @@ -5377,11 +5377,11 @@ void process_next_command() { gcode_M42(); break; - #if ENABLED(ENABLE_AUTO_BED_LEVELING) && ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) && ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) case 48: // M48 Z probe repeatability gcode_M48(); break; - #endif // ENABLE_AUTO_BED_LEVELING && Z_MIN_PROBE_REPEATABILITY_TEST + #endif // AUTO_BED_LEVELING_FEATURE && Z_MIN_PROBE_REPEATABILITY_TEST #if ENABLED(M100_FREE_MEMORY_WATCHER) case 100: @@ -5650,14 +5650,14 @@ void process_next_command() { gcode_M400(); break; - #if ENABLED(ENABLE_AUTO_BED_LEVELING) && (HAS_SERVO_ENDSTOPS || ENABLED(Z_PROBE_ALLEN_KEY)) && DISABLED(Z_PROBE_SLED) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) && (HAS_SERVO_ENDSTOPS || ENABLED(Z_PROBE_ALLEN_KEY)) && DISABLED(Z_PROBE_SLED) case 401: gcode_M401(); break; case 402: gcode_M402(); break; - #endif // ENABLE_AUTO_BED_LEVELING && (HAS_SERVO_ENDSTOPS || Z_PROBE_ALLEN_KEY) && !Z_PROBE_SLED + #endif // AUTO_BED_LEVELING_FEATURE && (HAS_SERVO_ENDSTOPS || Z_PROBE_ALLEN_KEY) && !Z_PROBE_SLED #if ENABLED(FILAMENT_SENSOR) case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width @@ -5799,7 +5799,7 @@ void clamp_to_software_endstops(float target[3]) { NOLESS(target[Y_AXIS], min_pos[Y_AXIS]); float negative_z_offset = 0; - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) if (zprobe_zoffset < 0) negative_z_offset += zprobe_zoffset; if (home_offset[Z_AXIS] < 0) negative_z_offset += home_offset[Z_AXIS]; #endif @@ -5849,7 +5849,7 @@ void clamp_to_software_endstops(float target[3]) { */ } - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) // Adjust print surface height by linear interpolation over the bed_level array. void adjust_delta(float cartesian[3]) { @@ -5889,7 +5889,7 @@ void clamp_to_software_endstops(float target[3]) { SERIAL_ECHOPGM(" offset="); SERIAL_ECHOLN(offset); */ } - #endif // ENABLE_AUTO_BED_LEVELING + #endif // AUTO_BED_LEVELING_FEATURE #endif // DELTA @@ -6008,7 +6008,7 @@ void mesh_plan_buffer_line(float x, float y, float z, const float e, float feed_ calculate_delta(target); - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) adjust_delta(target); #endif @@ -6236,7 +6236,7 @@ void plan_arc( #if ENABLED(DELTA) || ENABLED(SCARA) calculate_delta(arc_target); - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) adjust_delta(arc_target); #endif plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], arc_target[E_AXIS], feed_rate, active_extruder); @@ -6248,7 +6248,7 @@ void plan_arc( // Ensure last segment arrives at target location. #if ENABLED(DELTA) || ENABLED(SCARA) calculate_delta(target); - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) adjust_delta(target); #endif plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], target[E_AXIS], feed_rate, active_extruder); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index bf8dc1752..8c9f8341f 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -116,8 +116,8 @@ #if ENABLED(DELTA) #error MESH_BED_LEVELING does not yet support DELTA printers. #endif - #if ENABLED(ENABLE_AUTO_BED_LEVELING) - #error Select ENABLE_AUTO_BED_LEVELING or MESH_BED_LEVELING, not both. + #if ENABLED(AUTO_BED_LEVELING_FEATURE) + #error Select AUTO_BED_LEVELING_FEATURE or MESH_BED_LEVELING, not both. #endif #if MESH_NUM_X_POINTS > 7 || MESH_NUM_Y_POINTS > 7 #error MESH_NUM_X_POINTS and MESH_NUM_Y_POINTS need to be less than 8. @@ -127,7 +127,7 @@ /** * Auto Bed Leveling */ - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) /** * Require a Z min pin @@ -137,7 +137,7 @@ #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) #error You must have a Z min or Z probe endstop to enable Z_MIN_PROBE_REPEATABILITY_TEST. #else - #error ENABLE_AUTO_BED_LEVELING requires a Z min or Z probe endstop. Z_MIN_PIN or Z_MIN_PROBE_PIN must point to a valid hardware pin. + #error AUTO_BED_LEVELING_FEATURE requires a Z_MIN or Z_PROBE endstop. Z_MIN_PIN or Z_MIN_PROBE_PIN must point to a valid hardware pin. #endif #endif #endif @@ -207,7 +207,7 @@ #endif // !AUTO_BED_LEVELING_GRID - #endif // ENABLE_AUTO_BED_LEVELING + #endif // AUTO_BED_LEVELING_FEATURE /** * ULTIPANEL encoder @@ -221,7 +221,7 @@ */ #if ENABLED(DELTA) - #if ENABLED(ENABLE_AUTO_BED_LEVELING) + #if ENABLED(AUTO_BED_LEVELING_FEATURE) #if DISABLED(AUTO_BED_LEVELING_GRID) #error Only AUTO_BED_LEVELING_GRID is supported with DELTA. @@ -362,6 +362,8 @@ #error CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration. #elif defined(HAS_AUTOMATIC_VERSIONING) #error HAS_AUTOMATIC_VERSIONING deprecated - use USE_AUTOMATIC_VERSIONING instead + #elif defined(ENABLE_AUTO_BED_LEVELING) + #error ENABLE_AUTO_BED_LEVELING deprecated - use AUTO_BED_LEVELING_FEATURE instead #endif #endif //SANITYCHECK_H diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index b1f757e0a..edb2d97a2 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -171,7 +171,7 @@ void Config_StoreSettings() { for (uint8_t q=0; q #include "Marlin.h" -#if ENABLED(ENABLE_AUTO_BED_LEVELING) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) #include "vector_3.h" vector_3::vector_3() : x(0), y(0), z(0) { } @@ -134,5 +134,5 @@ void matrix_3x3::debug(const char title[]) { } } -#endif // ENABLE_AUTO_BED_LEVELING +#endif // AUTO_BED_LEVELING_FEATURE diff --git a/Marlin/vector_3.h b/Marlin/vector_3.h index 1c91e8b34..5aba35000 100644 --- a/Marlin/vector_3.h +++ b/Marlin/vector_3.h @@ -19,7 +19,7 @@ #ifndef VECTOR_3_H #define VECTOR_3_H -#if ENABLED(ENABLE_AUTO_BED_LEVELING) +#if ENABLED(AUTO_BED_LEVELING_FEATURE) class matrix_3x3; struct vector_3 @@ -57,6 +57,6 @@ struct matrix_3x3 void apply_rotation_xyz(matrix_3x3 rotationMatrix, float &x, float& y, float& z); -#endif // ENABLE_AUTO_BED_LEVELING +#endif // AUTO_BED_LEVELING_FEATURE #endif // VECTOR_3_H From 194f98ff958f5ed52a6c857fdfc848c5ec19dfe4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 9 Jul 2015 16:57:44 -0700 Subject: [PATCH 2/3] Debug messages for homing and leveling --- Marlin/Marlin_main.cpp | 312 ++++++++++++++++++++++++++++++++++++++++- 1 file changed, 306 insertions(+), 6 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index ea4b2fd21..ced6cdf08 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1033,6 +1033,19 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR); #endif //DUAL_X_CARRIAGE +#ifdef DEBUG_LEVELING + void print_xyz(const char *prefix, const float x, const float y, const float z) { + SERIAL_ECHO(prefix); + SERIAL_ECHOPAIR(": (", x); + SERIAL_ECHOPAIR(", ", y); + SERIAL_ECHOPAIR(", ", z); + SERIAL_ECHOLNPGM(")"); + } + void print_xyz(const char *prefix, const float xyz[]) { + print_xyz(prefix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]); + } +#endif + static void set_axis_is_at_home(AxisEnum axis) { #if ENABLED(DUAL_X_CARRIAGE) @@ -1098,6 +1111,12 @@ static void set_axis_is_at_home(AxisEnum axis) { #if ENABLED(AUTO_BED_LEVELING_FEATURE) && Z_HOME_DIR < 0 if (axis == Z_AXIS) current_position[Z_AXIS] -= zprobe_zoffset; #endif + + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("set_axis_is_at_home ", (unsigned long)axis); + SERIAL_ECHOPAIR(" > (home_offset[axis]==", home_offset[axis]); + print_xyz(") > current_position", current_position); + #endif } } @@ -1143,6 +1162,9 @@ static void setup_for_endstop_move() { saved_feedrate_multiplier = feedrate_multiplier; feedrate_multiplier = 100; refresh_cmd_timeout(); + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("setup_for_endstop_move > enable_endstops(true)"); + #endif enable_endstops(true); } @@ -1153,6 +1175,9 @@ static void setup_for_endstop_move() { * Calculate delta, start a line, and set current_position to destination */ void prepare_move_raw() { + #ifdef DEBUG_LEVELING + print_xyz("prepare_move_raw > destination", destination); + #endif refresh_cmd_timeout(); calculate_delta(destination); plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], (feedrate/60)*(feedrate_multiplier/100.0), active_extruder); @@ -1180,6 +1205,10 @@ static void setup_for_endstop_move() { current_position[Y_AXIS] = corrected_position.y; current_position[Z_AXIS] = corrected_position.z; + #ifdef DEBUG_LEVELING + print_xyz("set_bed_level_equation_lsq > current_position", current_position); + #endif + sync_plan_position(); } @@ -1209,6 +1238,10 @@ static void setup_for_endstop_move() { current_position[Y_AXIS] = corrected_position.y; current_position[Z_AXIS] = corrected_position.z; + #ifdef DEBUG_LEVELING + print_xyz("set_bed_level_equation_3pts > current_position", current_position); + #endif + sync_plan_position(); } @@ -1221,6 +1254,10 @@ static void setup_for_endstop_move() { float start_z = current_position[Z_AXIS]; long start_steps = st_get_position(Z_AXIS); + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("run_z_probe (DELTA) 1"); + #endif + // move down slowly until you find the bed feedrate = homing_feedrate[Z_AXIS] / 4; destination[Z_AXIS] = -10; @@ -1232,6 +1269,11 @@ static void setup_for_endstop_move() { long stop_steps = st_get_position(Z_AXIS); float mm = start_z - float(start_steps - stop_steps) / axis_steps_per_unit[Z_AXIS]; current_position[Z_AXIS] = mm; + + #ifdef DEBUG_LEVELING + print_xyz("run_z_probe (DELTA) 2 > current_position", current_position); + #endif + sync_plan_position_delta(); #else // !DELTA @@ -1265,6 +1307,10 @@ static void setup_for_endstop_move() { // Get the current stepper position after bumping an endstop current_position[Z_AXIS] = st_get_position_mm(Z_AXIS); sync_plan_position(); + + #ifdef DEBUG_LEVELING + print_xyz("run_z_probe > current_position", current_position); + #endif #endif // !DELTA } @@ -1276,6 +1322,10 @@ static void setup_for_endstop_move() { static void do_blocking_move_to(float x, float y, float z) { float oldFeedRate = feedrate; + #ifdef DEBUG_LEVELING + print_xyz("do_blocking_move_to", x, y, z); + #endif + #if ENABLED(DELTA) feedrate = XY_TRAVEL_SPEED; @@ -1312,6 +1362,9 @@ static void setup_for_endstop_move() { static void clean_up_after_endstop_move() { #if ENABLED(ENDSTOPS_ONLY_FOR_HOMING) + #if ENABLED(DEBUG_LEVELING) + SERIAL_ECHOLNPGM("clean_up_after_endstop_move > ENDSTOPS_ONLY_FOR_HOMING > enable_endstops(false)"); + #endif enable_endstops(false); #endif feedrate = saved_feedrate; @@ -1321,6 +1374,10 @@ static void setup_for_endstop_move() { static void deploy_z_probe() { + #ifdef DEBUG_LEVELING + print_xyz("deploy_z_probe > current_position", current_position); + #endif + #if HAS_SERVO_ENDSTOPS // Engage Z Servo endstop if enabled @@ -1411,6 +1468,10 @@ static void setup_for_endstop_move() { static void stow_z_probe(bool doRaise=true) { + #ifdef DEBUG_LEVELING + print_xyz("stow_z_probe > current_position", current_position); + #endif + #if HAS_SERVO_ENDSTOPS // Retract Z Servo endstop if enabled @@ -1418,6 +1479,12 @@ static void setup_for_endstop_move() { #if Z_RAISE_AFTER_PROBING > 0 if (doRaise) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("Raise Z (after) by ", (float)Z_RAISE_AFTER_PROBING); + SERIAL_EOL; + SERIAL_ECHOPAIR("> SERVO_ENDSTOPS > do_blocking_move_to_z ", current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING); + SERIAL_EOL; + #endif do_blocking_move_to_z(current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING); // this also updates current_position st_synchronize(); } @@ -1506,19 +1573,51 @@ static void setup_for_endstop_move() { // Probe bed height at position (x,y), returns the measured z value static float probe_pt(float x, float y, float z_before, ProbeAction probe_action=ProbeDeployAndStow, int verbose_level=1) { + + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("probe_pt >>>"); + SERIAL_ECHOPAIR("> ProbeAction:", (unsigned long)probe_action); + SERIAL_EOL; + print_xyz("> current_position", current_position); + #endif + + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("Z Raise to z_before ", z_before); + SERIAL_EOL; + SERIAL_ECHOPAIR("> do_blocking_move_to_z ", z_before); + SERIAL_EOL; + #endif + // Move Z up to the z_before height, then move the Z probe to the given XY do_blocking_move_to_z(z_before); // this also updates current_position + + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("> do_blocking_move_to_xy ", x - X_PROBE_OFFSET_FROM_EXTRUDER); + SERIAL_ECHOPAIR(", ", y - Y_PROBE_OFFSET_FROM_EXTRUDER); + SERIAL_EOL; + #endif + do_blocking_move_to_xy(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER); // this also updates current_position #if DISABLED(Z_PROBE_SLED) && DISABLED(Z_PROBE_ALLEN_KEY) - if (probe_action & ProbeDeploy) deploy_z_probe(); + if (probe_action & ProbeDeploy) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> ProbeDeploy"); + #endif + deploy_z_probe(); + } #endif run_z_probe(); float measured_z = current_position[Z_AXIS]; #if DISABLED(Z_PROBE_SLED) && DISABLED(Z_PROBE_ALLEN_KEY) - if (probe_action & ProbeStow) stow_z_probe(); + if (probe_action & ProbeStow) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> ProbeStow (stow_z_probe will do Z Raise)"); + #endif + stow_z_probe(); + } #endif if (verbose_level > 2) { @@ -1530,6 +1629,11 @@ static void setup_for_endstop_move() { SERIAL_PROTOCOL_F(measured_z, 3); SERIAL_EOL; } + + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("<<< probe_pt"); + #endif + return measured_z; } @@ -1585,6 +1689,9 @@ static void setup_for_endstop_move() { // Reset calibration results to zero. void reset_bed_level() { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("reset_bed_level"); + #endif for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) { for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) { bed_level[x][y] = 0.0; @@ -1620,6 +1727,10 @@ static void setup_for_endstop_move() { * offset[in] The additional distance to move to adjust docking location */ static void dock_sled(bool dock, int offset=0) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("dock_sled", dock); + SERIAL_EOL; + #endif if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) { LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN); SERIAL_ECHO_START; @@ -1654,6 +1765,11 @@ static void setup_for_endstop_move() { #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS) static void homeaxis(AxisEnum axis) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR(">>> homeaxis(", (unsigned long)axis); + SERIAL_CHAR(')'); + SERIAL_EOL; + #endif #define HOMEAXIS_DO(LETTER) \ ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1)) @@ -1706,6 +1822,9 @@ static void homeaxis(AxisEnum axis) { current_position[axis] = 0; sync_plan_position(); + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> enable_endstops(false)"); + #endif enable_endstops(false); // Disable endstops while moving away // Move away from the endstop by the axis HOME_BUMP_MM @@ -1713,6 +1832,9 @@ static void homeaxis(AxisEnum axis) { line_to_destination(); st_synchronize(); + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> enable_endstops(true)"); + #endif enable_endstops(true); // Enable endstops for next homing move // Slow down the feedrate for the next move @@ -1723,6 +1845,10 @@ static void homeaxis(AxisEnum axis) { line_to_destination(); st_synchronize(); + #ifdef DEBUG_LEVELING + print_xyz("> TRIGGER ENDSTOP > current_position", current_position); + #endif + #if ENABLED(Z_DUAL_ENDSTOPS) if (axis == Z_AXIS) { float adj = fabs(z_endstop_adj); @@ -1751,19 +1877,39 @@ static void homeaxis(AxisEnum axis) { #if ENABLED(DELTA) // retrace by the amount specified in endstop_adj if (endstop_adj[axis] * axis_home_dir < 0) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> enable_endstops(false)"); + #endif enable_endstops(false); // Disable endstops while moving away sync_plan_position(); destination[axis] = endstop_adj[axis]; + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("> endstop_adj = ", endstop_adj[axis]); + print_xyz(" > destination", destination); + #endif line_to_destination(); st_synchronize(); + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> enable_endstops(true)"); + #endif enable_endstops(true); // Enable endstops for next homing move } + #ifdef DEBUG_LEVELING + else { + SERIAL_ECHOPAIR("> endstop_adj * axis_home_dir = ", endstop_adj[axis] * axis_home_dir); + SERIAL_EOL; + } + #endif #endif // Set the axis position to its home position (plus home offsets) set_axis_is_at_home(axis); sync_plan_position(); + #ifdef DEBUG_LEVELING + print_xyz("> AFTER set_axis_is_at_home > current_position", current_position); + #endif + destination[axis] = current_position[axis]; feedrate = 0.0; endstops_hit_on_purpose(); // clear endstop hit flags @@ -1780,7 +1926,12 @@ static void homeaxis(AxisEnum axis) { // Deploy a Z probe if there is one, and homing towards the bed if (axis == Z_AXIS) { - if (axis_home_dir < 0) stow_z_probe(); + if (axis_home_dir < 0) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> SERVO_LEVELING > stow_z_probe"); + #endif + stow_z_probe(); + } } else @@ -1789,12 +1940,22 @@ static void homeaxis(AxisEnum axis) { { #if HAS_SERVO_ENDSTOPS // Retract Servo endstop if enabled - if (servo_endstop_id[axis] >= 0) + if (servo_endstop_id[axis] >= 0) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> SERVO_ENDSTOPS > Stow with servo.move()"); + #endif servo[servo_endstop_id[axis]].move(servo_endstop_angle[axis][1]); + } #endif } } + + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("<<< homeaxis(", (unsigned long)axis); + SERIAL_CHAR(')'); + SERIAL_EOL; + #endif } #if ENABLED(FWRETRACT) @@ -1996,6 +2157,10 @@ inline void gcode_G4() { */ inline void gcode_G28() { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("gcode_G28 >>>"); + #endif + // Wait for planner moves to finish! st_synchronize(); @@ -2044,6 +2209,10 @@ inline void gcode_G28() { sync_plan_position_delta(); + #ifdef DEBUG_LEVELING + print_xyz("(DELTA) > current_position", current_position); + #endif + #else // NOT DELTA bool homeX = code_seen(axis_codes[X_AXIS]), @@ -2057,12 +2226,20 @@ inline void gcode_G28() { #if Z_HOME_DIR > 0 // If homing away from BED do Z first HOMEAXIS(Z); + #ifdef DEBUG_LEVELING + print_xyz("> HOMEAXIS(Z) > current_position", current_position); + #endif #elif DISABLED(Z_SAFE_HOMING) && defined(Z_RAISE_BEFORE_HOMING) && Z_RAISE_BEFORE_HOMING > 0 // Raise Z before homing any other axes // (Does this need to be "negative home direction?" Why not just use Z_RAISE_BEFORE_HOMING?) destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); + SERIAL_EOL; + print_xyz("> (home_all_axis || homeZ) > destination", destination); + #endif feedrate = max_feedrate[Z_AXIS] * 60; line_to_destination(); st_synchronize(); @@ -2099,6 +2276,10 @@ inline void gcode_G28() { set_axis_is_at_home(Y_AXIS); sync_plan_position(); + #ifdef DEBUG_LEVELING + print_xyz("> QUICK_HOME > current_position 1", current_position); + #endif + destination[X_AXIS] = current_position[X_AXIS]; destination[Y_AXIS] = current_position[Y_AXIS]; line_to_destination(); @@ -2111,6 +2292,10 @@ inline void gcode_G28() { #if DISABLED(SCARA) current_position[Z_AXIS] = destination[Z_AXIS]; #endif + + #ifdef DEBUG_LEVELING + print_xyz("> QUICK_HOME > current_position 2", current_position); + #endif } #endif // QUICK_HOME @@ -2137,11 +2322,19 @@ inline void gcode_G28() { #else HOMEAXIS(X); #endif + #ifdef DEBUG_LEVELING + print_xyz("> homeX", current_position); + #endif } #if DISABLED(HOME_Y_BEFORE_X) // Home Y - if (home_all_axis || homeY) HOMEAXIS(Y); + if (home_all_axis || homeY) { + HOMEAXIS(Y); + #ifdef DEBUG_LEVELING + print_xyz("> homeY", current_position); + #endif + } #endif // Home Z last if homing towards the bed @@ -2151,6 +2344,10 @@ inline void gcode_G28() { #if ENABLED(Z_SAFE_HOMING) + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> Z_SAFE_HOMING >>>"); + #endif + if (home_all_axis) { current_position[Z_AXIS] = 0; @@ -2165,6 +2362,14 @@ inline void gcode_G28() { destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - Y_PROBE_OFFSET_FROM_EXTRUDER); destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); // Set destination away from bed feedrate = XY_TRAVEL_SPEED; + + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); + SERIAL_EOL; + print_xyz("> home_all_axis > current_position", current_position); + print_xyz("> home_all_axis > destination", destination); + #endif + // This could potentially move X, Y, Z all together line_to_destination(); st_synchronize(); @@ -2197,6 +2402,14 @@ inline void gcode_G28() { // NOTE: This should always just be Z_RAISE_BEFORE_HOMING unless...??? destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); feedrate = max_feedrate[Z_AXIS] * 60; // feedrate (mm/m) = max_feedrate (mm/s) + + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); + SERIAL_EOL; + print_xyz("> homeZ > current_position", current_position); + print_xyz("> homeZ > destination", destination); + #endif + line_to_destination(); st_synchronize(); @@ -2217,12 +2430,20 @@ inline void gcode_G28() { } // !home_all_axes && homeZ + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("<<< Z_SAFE_HOMING"); + #endif + #else // !Z_SAFE_HOMING HOMEAXIS(Z); #endif // !Z_SAFE_HOMING + #ifdef DEBUG_LEVELING + print_xyz("> (home_all_axis || homeZ) > final", current_position); + #endif + } // home_all_axis || homeZ #endif // Z_HOME_DIR < 0 @@ -2236,6 +2457,9 @@ inline void gcode_G28() { #endif #if ENABLED(ENDSTOPS_ONLY_FOR_HOMING) + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("ENDSTOPS_ONLY_FOR_HOMING enable_endstops(false)"); + #endif enable_endstops(false); #endif @@ -2251,6 +2475,9 @@ inline void gcode_G28() { current_position[Z_AXIS] = MESH_HOME_SEARCH_Z; sync_plan_position(); mbl.active = 1; + #ifdef DEBUG_LEVELING + print_xyz("mbl_was_active > current_position", current_position); + #endif } #endif @@ -2258,6 +2485,11 @@ inline void gcode_G28() { feedrate_multiplier = saved_feedrate_multiplier; refresh_cmd_timeout(); endstops_hit_on_purpose(); // clear endstop hit flags + + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("<<< gcode_G28"); + #endif + } #if ENABLED(MESH_BED_LEVELING) @@ -2443,6 +2675,10 @@ inline void gcode_G28() { */ inline void gcode_G29() { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("gcode_G29 >>>"); + #endif + // Don't allow auto-leveling without homing first if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) { LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN); @@ -2601,6 +2837,19 @@ inline void gcode_G28() { float measured_z, z_before = probePointCounter ? Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS] : Z_RAISE_BEFORE_PROBING; + if (probePointCounter) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("z_before = (between) ", (float)(Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS])); + SERIAL_EOL; + #endif + } + else { + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("z_before = (before) ", (float)Z_RAISE_BEFORE_PROBING); + SERIAL_EOL; + #endif + } + #if ENABLED(DELTA) // Avoid probing the corners (outside the round or hexagon print surface) on a delta printer. float distance_from_center = sqrt(xProbe*xProbe + yProbe*yProbe); @@ -2638,6 +2887,10 @@ inline void gcode_G28() { } //xProbe } //yProbe + #ifdef DEBUG_LEVELING + print_xyz("> probing complete > current_position", current_position); + #endif + clean_up_after_endstop_move(); #if ENABLED(DELTA) @@ -2734,6 +2987,10 @@ inline void gcode_G28() { #else // !AUTO_BED_LEVELING_GRID + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("> 3-point Leveling"); + #endif + // Actions for each probe ProbeAction p1, p2, p3; if (deploy_probe_for_each_reading) @@ -2763,6 +3020,13 @@ inline void gcode_G28() { z_tmp = current_position[Z_AXIS], real_z = st_get_position_mm(Z_AXIS); //get the real Z (since plan_get_position is now correcting the plane) + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > z_tmp = ", z_tmp); + SERIAL_EOL; + SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > real_z = ", real_z); + SERIAL_EOL; + #endif + apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); // Apply the correction sending the Z probe offset // Get the current Z position and send it to the planner. @@ -2781,6 +3045,11 @@ inline void gcode_G28() { // adjust for inaccurate endstops, not for reasonably accurate probes. If it were // added here, it could be seen as a compensating factor for the Z probe. // + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("> AFTER apply_rotation_xyz > z_tmp = ", z_tmp); + SERIAL_EOL; + #endif + current_position[Z_AXIS] = -zprobe_zoffset + (z_tmp - real_z) #if HAS_SERVO_ENDSTOPS || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) + Z_RAISE_AFTER_PROBING @@ -2788,6 +3057,10 @@ inline void gcode_G28() { ; // current_position[Z_AXIS] += home_offset[Z_AXIS]; // The Z probe determines Z=0, not "Z home" sync_plan_position(); + + #ifdef DEBUG_LEVELING + print_xyz("> corrected Z in G29", current_position); + #endif } #endif // !DELTA @@ -2798,9 +3071,18 @@ inline void gcode_G28() { #endif #ifdef Z_PROBE_END_SCRIPT + #ifdef DEBUG_LEVELING + SERIAL_ECHO("Z Probe End Script: "); + SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT); + #endif enqueuecommands_P(PSTR(Z_PROBE_END_SCRIPT)); st_synchronize(); #endif + + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("<<< gcode_G29"); + #endif + } #if DISABLED(Z_PROBE_SLED) @@ -4095,11 +4377,23 @@ inline void gcode_M206() { * M666: Set delta endstop adjustment */ inline void gcode_M666() { + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM(">>> gcode_M666"); + #endif for (int8_t i = X_AXIS; i <= Z_AXIS; i++) { if (code_seen(axis_codes[i])) { endstop_adj[i] = code_value(); + #ifdef DEBUG_LEVELING + SERIAL_ECHOPGM("endstop_adj["); + SERIAL_ECHO(axis_codes[i]); + SERIAL_ECHOPAIR("] = ", endstop_adj[i]); + SERIAL_EOL; + #endif } } + #ifdef DEBUG_LEVELING + SERIAL_ECHOLNPGM("<<< gcode_M666"); + #endif } #elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS) /** @@ -5801,7 +6095,13 @@ void clamp_to_software_endstops(float target[3]) { float negative_z_offset = 0; #if ENABLED(AUTO_BED_LEVELING_FEATURE) if (zprobe_zoffset < 0) negative_z_offset += zprobe_zoffset; - if (home_offset[Z_AXIS] < 0) negative_z_offset += home_offset[Z_AXIS]; + if (home_offset[Z_AXIS] < 0) { + #ifdef DEBUG_LEVELING + SERIAL_ECHOPAIR("> clamp_to_software_endstops > Add home_offset[Z_AXIS]:", home_offset[Z_AXIS]); + SERIAL_EOL; + #endif + negative_z_offset += home_offset[Z_AXIS]; + } #endif NOLESS(target[Z_AXIS], min_pos[Z_AXIS] + negative_z_offset); } From 20b47721553f0be3554b7143270dec4a809127d6 Mon Sep 17 00:00:00 2001 From: Richard Wackerbarth Date: Wed, 5 Aug 2015 06:40:36 -0500 Subject: [PATCH 3/3] Create DEBUG_LEVELING_FEATURE --- Marlin/Configuration.h | 5 +- Marlin/Marlin.h | 3 +- Marlin/Marlin_main.cpp | 638 +++++++++++++++++++++++++---------------- Marlin/language.h | 1 + 4 files changed, 391 insertions(+), 256 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index bc972625b..6b3dd0d7e 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -510,8 +510,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l //#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell. //#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like. -// If you have enabled the bed auto leveling and are using the same Z probe for Z homing, -// it is highly recommended you let this Z_SAFE_HOMING enabled!!! + + //If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing, + //it is highly recommended you let this Z_SAFE_HOMING enabled!!! #define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area. // When defined, it will: diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 33487c869..1496913dd 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -221,7 +221,8 @@ enum DebugFlags { DEBUG_INFO = BIT(1), DEBUG_ERRORS = BIT(2), DEBUG_DRYRUN = BIT(3), - DEBUG_COMMUNICATION = BIT(4) + DEBUG_COMMUNICATION = BIT(4), + DEBUG_LEVELING = BIT(5) }; extern uint8_t marlin_debug_flags; diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index ced6cdf08..4439d4d1d 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -154,7 +154,7 @@ * M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work. * M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating * Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling - * M200 - set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).:D- + * M200 - set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).:D- * M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) * M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!! * M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec @@ -341,7 +341,7 @@ bool target_direction; #endif // FWRETRACT #if ENABLED(ULTIPANEL) && HAS_POWER_SWITCH - bool powersupply = + bool powersupply = #if ENABLED(PS_DEFAULT_OFF) false #else @@ -358,9 +358,9 @@ bool target_direction; // these are the default values, can be overriden with M665 float delta_radius = DELTA_RADIUS; float delta_tower1_x = -SIN_60 * delta_radius; // front left tower - float delta_tower1_y = -COS_60 * delta_radius; + float delta_tower1_y = -COS_60 * delta_radius; float delta_tower2_x = SIN_60 * delta_radius; // front right tower - float delta_tower2_y = -COS_60 * delta_radius; + float delta_tower2_y = -COS_60 * delta_radius; float delta_tower3_x = 0; // back middle tower float delta_tower3_y = delta_radius; float delta_diagonal_rod = DELTA_DIAGONAL_ROD; @@ -692,7 +692,7 @@ void setup() { #endif // Z_PROBE_SLED setup_homepin(); - + #ifdef STAT_LED_RED pinMode(STAT_LED_RED, OUTPUT); digitalWrite(STAT_LED_RED, LOW); // turn it off @@ -701,7 +701,7 @@ void setup() { #ifdef STAT_LED_BLUE pinMode(STAT_LED_BLUE, OUTPUT); digitalWrite(STAT_LED_BLUE, LOW); // turn it off - #endif + #endif } /** @@ -775,11 +775,11 @@ void gcode_line_error(const char *err, bool doFlush=true) { void get_command() { if (drain_queued_commands_P()) return; // priority is given to non-serial commands - + #if ENABLED(NO_TIMEOUTS) static millis_t last_command_time = 0; millis_t ms = millis(); - + if (!MYSERIAL.available() && commands_in_queue == 0 && ms - last_command_time > NO_TIMEOUTS) { SERIAL_ECHOLNPGM(MSG_WAIT); last_command_time = ms; @@ -870,7 +870,7 @@ void get_command() { LCD_MESSAGEPGM(MSG_STOPPED); break; } - } + } } // If command was e-stop process now @@ -1033,7 +1033,7 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR); #endif //DUAL_X_CARRIAGE -#ifdef DEBUG_LEVELING +#if ENABLED(DEBUG_LEVELING_FEATURE) void print_xyz(const char *prefix, const float x, const float y, const float z) { SERIAL_ECHO(prefix); SERIAL_ECHOPAIR(": (", x); @@ -1067,7 +1067,7 @@ static void set_axis_is_at_home(AxisEnum axis) { #endif #if ENABLED(SCARA) - + if (axis == X_AXIS || axis == Y_AXIS) { float homeposition[3]; @@ -1075,28 +1075,28 @@ static void set_axis_is_at_home(AxisEnum axis) { // SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]); // SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]); - // Works out real Homeposition angles using inverse kinematics, + // Works out real Homeposition angles using inverse kinematics, // and calculates homing offset using forward kinematics calculate_delta(homeposition); - + // SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]); // SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]); - + for (int i = 0; i < 2; i++) delta[i] -= home_offset[i]; - + // SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]); // SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]); // SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]); // SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]); - + calculate_SCARA_forward_Transform(delta); - + // SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]); // SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]); - + current_position[axis] = delta[axis]; - - // SCARA home positions are based on configuration since the actual limits are determined by the + + // SCARA home positions are based on configuration since the actual limits are determined by the // inverse kinematic transform. min_pos[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis)); max_pos[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis)); @@ -1112,10 +1112,12 @@ static void set_axis_is_at_home(AxisEnum axis) { if (axis == Z_AXIS) current_position[Z_AXIS] -= zprobe_zoffset; #endif - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("set_axis_is_at_home ", (unsigned long)axis); - SERIAL_ECHOPAIR(" > (home_offset[axis]==", home_offset[axis]); - print_xyz(") > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("set_axis_is_at_home ", (unsigned long)axis); + SERIAL_ECHOPAIR(" > (home_offset[axis]==", home_offset[axis]); + print_xyz(") > current_position", current_position); + } #endif } } @@ -1162,8 +1164,10 @@ static void setup_for_endstop_move() { saved_feedrate_multiplier = feedrate_multiplier; feedrate_multiplier = 100; refresh_cmd_timeout(); - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("setup_for_endstop_move > enable_endstops(true)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("setup_for_endstop_move > enable_endstops(true)"); + } #endif enable_endstops(true); } @@ -1175,8 +1179,10 @@ static void setup_for_endstop_move() { * Calculate delta, start a line, and set current_position to destination */ void prepare_move_raw() { - #ifdef DEBUG_LEVELING - print_xyz("prepare_move_raw > destination", destination); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("prepare_move_raw > destination", destination); + } #endif refresh_cmd_timeout(); calculate_delta(destination); @@ -1205,8 +1211,10 @@ static void setup_for_endstop_move() { current_position[Y_AXIS] = corrected_position.y; current_position[Z_AXIS] = corrected_position.z; - #ifdef DEBUG_LEVELING - print_xyz("set_bed_level_equation_lsq > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("set_bed_level_equation_lsq > current_position", current_position); + } #endif sync_plan_position(); @@ -1238,8 +1246,10 @@ static void setup_for_endstop_move() { current_position[Y_AXIS] = corrected_position.y; current_position[Z_AXIS] = corrected_position.z; - #ifdef DEBUG_LEVELING - print_xyz("set_bed_level_equation_3pts > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("set_bed_level_equation_3pts > current_position", current_position); + } #endif sync_plan_position(); @@ -1250,12 +1260,14 @@ static void setup_for_endstop_move() { static void run_z_probe() { #if ENABLED(DELTA) - + float start_z = current_position[Z_AXIS]; long start_steps = st_get_position(Z_AXIS); - - #ifdef DEBUG_LEVELING + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { SERIAL_ECHOLNPGM("run_z_probe (DELTA) 1"); + } #endif // move down slowly until you find the bed @@ -1264,18 +1276,20 @@ static void setup_for_endstop_move() { prepare_move_raw(); // this will also set_current_to_destination st_synchronize(); endstops_hit_on_purpose(); // clear endstop hit flags - + // we have to let the planner know where we are right now as it is not where we said to go. long stop_steps = st_get_position(Z_AXIS); float mm = start_z - float(start_steps - stop_steps) / axis_steps_per_unit[Z_AXIS]; current_position[Z_AXIS] = mm; - #ifdef DEBUG_LEVELING - print_xyz("run_z_probe (DELTA) 2 > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("run_z_probe (DELTA) 2 > current_position", current_position); + } #endif sync_plan_position_delta(); - + #else // !DELTA plan_bed_level_matrix.set_to_identity(); @@ -1308,10 +1322,12 @@ static void setup_for_endstop_move() { current_position[Z_AXIS] = st_get_position_mm(Z_AXIS); sync_plan_position(); - #ifdef DEBUG_LEVELING - print_xyz("run_z_probe > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("run_z_probe > current_position", current_position); + } #endif - + #endif // !DELTA } @@ -1322,14 +1338,16 @@ static void setup_for_endstop_move() { static void do_blocking_move_to(float x, float y, float z) { float oldFeedRate = feedrate; - #ifdef DEBUG_LEVELING - print_xyz("do_blocking_move_to", x, y, z); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("do_blocking_move_to", x, y, z); + } #endif #if ENABLED(DELTA) feedrate = XY_TRAVEL_SPEED; - + destination[X_AXIS] = x; destination[Y_AXIS] = y; destination[Z_AXIS] = z; @@ -1362,8 +1380,10 @@ static void setup_for_endstop_move() { static void clean_up_after_endstop_move() { #if ENABLED(ENDSTOPS_ONLY_FOR_HOMING) - #if ENABLED(DEBUG_LEVELING) - SERIAL_ECHOLNPGM("clean_up_after_endstop_move > ENDSTOPS_ONLY_FOR_HOMING > enable_endstops(false)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("clean_up_after_endstop_move > ENDSTOPS_ONLY_FOR_HOMING > enable_endstops(false)"); + } #endif enable_endstops(false); #endif @@ -1374,8 +1394,10 @@ static void setup_for_endstop_move() { static void deploy_z_probe() { - #ifdef DEBUG_LEVELING - print_xyz("deploy_z_probe > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("deploy_z_probe > current_position", current_position); + } #endif #if HAS_SERVO_ENDSTOPS @@ -1468,8 +1490,10 @@ static void setup_for_endstop_move() { static void stow_z_probe(bool doRaise=true) { - #ifdef DEBUG_LEVELING - print_xyz("stow_z_probe > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("stow_z_probe > current_position", current_position); + } #endif #if HAS_SERVO_ENDSTOPS @@ -1479,11 +1503,13 @@ static void setup_for_endstop_move() { #if Z_RAISE_AFTER_PROBING > 0 if (doRaise) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("Raise Z (after) by ", (float)Z_RAISE_AFTER_PROBING); - SERIAL_EOL; - SERIAL_ECHOPAIR("> SERVO_ENDSTOPS > do_blocking_move_to_z ", current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("Raise Z (after) by ", (float)Z_RAISE_AFTER_PROBING); + SERIAL_EOL; + SERIAL_ECHOPAIR("> SERVO_ENDSTOPS > do_blocking_move_to_z ", current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING); + SERIAL_EOL; + } #endif do_blocking_move_to_z(current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING); // this also updates current_position st_synchronize(); @@ -1522,7 +1548,7 @@ static void setup_for_endstop_move() { } destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_STOW_2_Z; prepare_move_raw(); - + // Move up for safety if (Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE != Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE) { feedrate = Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE; @@ -1535,13 +1561,13 @@ static void setup_for_endstop_move() { } destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_STOW_3_Z; prepare_move_raw(); - + // Home XY for safety feedrate = homing_feedrate[X_AXIS]/2; destination[X_AXIS] = 0; destination[Y_AXIS] = 0; prepare_move_raw(); // this will also set_current_to_destination - + st_synchronize(); #if ENABLED(Z_MIN_PROBE_ENDSTOP) @@ -1574,35 +1600,43 @@ static void setup_for_endstop_move() { // Probe bed height at position (x,y), returns the measured z value static float probe_pt(float x, float y, float z_before, ProbeAction probe_action=ProbeDeployAndStow, int verbose_level=1) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("probe_pt >>>"); - SERIAL_ECHOPAIR("> ProbeAction:", (unsigned long)probe_action); - SERIAL_EOL; - print_xyz("> current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("probe_pt >>>"); + SERIAL_ECHOPAIR("> ProbeAction:", (unsigned long)probe_action); + SERIAL_EOL; + print_xyz("> current_position", current_position); + } #endif - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("Z Raise to z_before ", z_before); - SERIAL_EOL; - SERIAL_ECHOPAIR("> do_blocking_move_to_z ", z_before); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("Z Raise to z_before ", z_before); + SERIAL_EOL; + SERIAL_ECHOPAIR("> do_blocking_move_to_z ", z_before); + SERIAL_EOL; + } #endif // Move Z up to the z_before height, then move the Z probe to the given XY do_blocking_move_to_z(z_before); // this also updates current_position - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("> do_blocking_move_to_xy ", x - X_PROBE_OFFSET_FROM_EXTRUDER); - SERIAL_ECHOPAIR(", ", y - Y_PROBE_OFFSET_FROM_EXTRUDER); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("> do_blocking_move_to_xy ", x - X_PROBE_OFFSET_FROM_EXTRUDER); + SERIAL_ECHOPAIR(", ", y - Y_PROBE_OFFSET_FROM_EXTRUDER); + SERIAL_EOL; + } #endif do_blocking_move_to_xy(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER); // this also updates current_position #if DISABLED(Z_PROBE_SLED) && DISABLED(Z_PROBE_ALLEN_KEY) if (probe_action & ProbeDeploy) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> ProbeDeploy"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> ProbeDeploy"); + } #endif deploy_z_probe(); } @@ -1613,8 +1647,10 @@ static void setup_for_endstop_move() { #if DISABLED(Z_PROBE_SLED) && DISABLED(Z_PROBE_ALLEN_KEY) if (probe_action & ProbeStow) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> ProbeStow (stow_z_probe will do Z Raise)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> ProbeStow (stow_z_probe will do Z Raise)"); + } #endif stow_z_probe(); } @@ -1630,8 +1666,10 @@ static void setup_for_endstop_move() { SERIAL_EOL; } - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("<<< probe_pt"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("<<< probe_pt"); + } #endif return measured_z; @@ -1689,8 +1727,10 @@ static void setup_for_endstop_move() { // Reset calibration results to zero. void reset_bed_level() { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("reset_bed_level"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("reset_bed_level"); + } #endif for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) { for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) { @@ -1727,9 +1767,11 @@ static void setup_for_endstop_move() { * offset[in] The additional distance to move to adjust docking location */ static void dock_sled(bool dock, int offset=0) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("dock_sled", dock); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("dock_sled", dock); + SERIAL_EOL; + } #endif if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) { LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN); @@ -1765,10 +1807,12 @@ static void setup_for_endstop_move() { #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS) static void homeaxis(AxisEnum axis) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR(">>> homeaxis(", (unsigned long)axis); - SERIAL_CHAR(')'); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR(">>> homeaxis(", (unsigned long)axis); + SERIAL_CHAR(')'); + SERIAL_EOL; + } #endif #define HOMEAXIS_DO(LETTER) \ ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1)) @@ -1791,7 +1835,7 @@ static void homeaxis(AxisEnum axis) { if (axis_home_dir < 0) dock_sled(false); } #endif - + #if SERVO_LEVELING && DISABLED(Z_PROBE_SLED) // Deploy a Z probe if there is one, and homing towards the bed @@ -1822,8 +1866,10 @@ static void homeaxis(AxisEnum axis) { current_position[axis] = 0; sync_plan_position(); - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> enable_endstops(false)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> enable_endstops(false)"); + } #endif enable_endstops(false); // Disable endstops while moving away @@ -1832,8 +1878,10 @@ static void homeaxis(AxisEnum axis) { line_to_destination(); st_synchronize(); - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> enable_endstops(true)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> enable_endstops(true)"); + } #endif enable_endstops(true); // Enable endstops for next homing move @@ -1845,8 +1893,10 @@ static void homeaxis(AxisEnum axis) { line_to_destination(); st_synchronize(); - #ifdef DEBUG_LEVELING - print_xyz("> TRIGGER ENDSTOP > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> TRIGGER ENDSTOP > current_position", current_position); + } #endif #if ENABLED(Z_DUAL_ENDSTOPS) @@ -1877,27 +1927,35 @@ static void homeaxis(AxisEnum axis) { #if ENABLED(DELTA) // retrace by the amount specified in endstop_adj if (endstop_adj[axis] * axis_home_dir < 0) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> enable_endstops(false)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> enable_endstops(false)"); + } #endif enable_endstops(false); // Disable endstops while moving away sync_plan_position(); destination[axis] = endstop_adj[axis]; - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("> endstop_adj = ", endstop_adj[axis]); - print_xyz(" > destination", destination); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("> endstop_adj = ", endstop_adj[axis]); + print_xyz(" > destination", destination); + } #endif line_to_destination(); st_synchronize(); - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> enable_endstops(true)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> enable_endstops(true)"); + } #endif enable_endstops(true); // Enable endstops for next homing move } - #ifdef DEBUG_LEVELING + #if ENABLED(DEBUG_LEVELING_FEATURE) else { - SERIAL_ECHOPAIR("> endstop_adj * axis_home_dir = ", endstop_adj[axis] * axis_home_dir); - SERIAL_EOL; + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("> endstop_adj * axis_home_dir = ", endstop_adj[axis] * axis_home_dir); + SERIAL_EOL; + } } #endif #endif @@ -1906,8 +1964,10 @@ static void homeaxis(AxisEnum axis) { set_axis_is_at_home(axis); sync_plan_position(); - #ifdef DEBUG_LEVELING - print_xyz("> AFTER set_axis_is_at_home > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> AFTER set_axis_is_at_home > current_position", current_position); + } #endif destination[axis] = current_position[axis]; @@ -1919,7 +1979,7 @@ static void homeaxis(AxisEnum axis) { // bring Z probe back if (axis == Z_AXIS) { if (axis_home_dir < 0) dock_sled(true); - } + } #endif #if SERVO_LEVELING && DISABLED(Z_PROBE_SLED) @@ -1927,8 +1987,10 @@ static void homeaxis(AxisEnum axis) { // Deploy a Z probe if there is one, and homing towards the bed if (axis == Z_AXIS) { if (axis_home_dir < 0) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> SERVO_LEVELING > stow_z_probe"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> SERVO_LEVELING > stow_z_probe"); + } #endif stow_z_probe(); } @@ -1941,8 +2003,10 @@ static void homeaxis(AxisEnum axis) { #if HAS_SERVO_ENDSTOPS // Retract Servo endstop if enabled if (servo_endstop_id[axis] >= 0) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> SERVO_ENDSTOPS > Stow with servo.move()"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> SERVO_ENDSTOPS > Stow with servo.move()"); + } #endif servo[servo_endstop_id[axis]].move(servo_endstop_angle[axis][1]); } @@ -1951,10 +2015,12 @@ static void homeaxis(AxisEnum axis) { } - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("<<< homeaxis(", (unsigned long)axis); - SERIAL_CHAR(')'); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("<<< homeaxis(", (unsigned long)axis); + SERIAL_CHAR(')'); + SERIAL_EOL; + } #endif } @@ -2157,8 +2223,10 @@ inline void gcode_G4() { */ inline void gcode_G28() { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("gcode_G28 >>>"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("gcode_G28 >>>"); + } #endif // Wait for planner moves to finish! @@ -2209,8 +2277,10 @@ inline void gcode_G28() { sync_plan_position_delta(); - #ifdef DEBUG_LEVELING - print_xyz("(DELTA) > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("(DELTA) > current_position", current_position); + } #endif #else // NOT DELTA @@ -2226,8 +2296,10 @@ inline void gcode_G28() { #if Z_HOME_DIR > 0 // If homing away from BED do Z first HOMEAXIS(Z); - #ifdef DEBUG_LEVELING - print_xyz("> HOMEAXIS(Z) > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> HOMEAXIS(Z) > current_position", current_position); + } #endif #elif DISABLED(Z_SAFE_HOMING) && defined(Z_RAISE_BEFORE_HOMING) && Z_RAISE_BEFORE_HOMING > 0 @@ -2235,10 +2307,12 @@ inline void gcode_G28() { // Raise Z before homing any other axes // (Does this need to be "negative home direction?" Why not just use Z_RAISE_BEFORE_HOMING?) destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); - SERIAL_EOL; - print_xyz("> (home_all_axis || homeZ) > destination", destination); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); + SERIAL_EOL; + print_xyz("> (home_all_axis || homeZ) > destination", destination); + } #endif feedrate = max_feedrate[Z_AXIS] * 60; line_to_destination(); @@ -2276,8 +2350,10 @@ inline void gcode_G28() { set_axis_is_at_home(Y_AXIS); sync_plan_position(); - #ifdef DEBUG_LEVELING - print_xyz("> QUICK_HOME > current_position 1", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> QUICK_HOME > current_position 1", current_position); + } #endif destination[X_AXIS] = current_position[X_AXIS]; @@ -2293,8 +2369,10 @@ inline void gcode_G28() { current_position[Z_AXIS] = destination[Z_AXIS]; #endif - #ifdef DEBUG_LEVELING - print_xyz("> QUICK_HOME > current_position 2", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> QUICK_HOME > current_position 2", current_position); + } #endif } @@ -2322,8 +2400,10 @@ inline void gcode_G28() { #else HOMEAXIS(X); #endif - #ifdef DEBUG_LEVELING - print_xyz("> homeX", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> homeX", current_position); + } #endif } @@ -2331,8 +2411,10 @@ inline void gcode_G28() { // Home Y if (home_all_axis || homeY) { HOMEAXIS(Y); - #ifdef DEBUG_LEVELING - print_xyz("> homeY", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> homeY", current_position); + } #endif } #endif @@ -2344,8 +2426,10 @@ inline void gcode_G28() { #if ENABLED(Z_SAFE_HOMING) - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> Z_SAFE_HOMING >>>"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> Z_SAFE_HOMING >>>"); + } #endif if (home_all_axis) { @@ -2363,11 +2447,13 @@ inline void gcode_G28() { destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); // Set destination away from bed feedrate = XY_TRAVEL_SPEED; - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); - SERIAL_EOL; - print_xyz("> home_all_axis > current_position", current_position); - print_xyz("> home_all_axis > destination", destination); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); + SERIAL_EOL; + print_xyz("> home_all_axis > current_position", current_position); + print_xyz("> home_all_axis > destination", destination); + } #endif // This could potentially move X, Y, Z all together @@ -2403,11 +2489,13 @@ inline void gcode_G28() { destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); feedrate = max_feedrate[Z_AXIS] * 60; // feedrate (mm/m) = max_feedrate (mm/s) - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); - SERIAL_EOL; - print_xyz("> homeZ > current_position", current_position); - print_xyz("> homeZ > destination", destination); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING); + SERIAL_EOL; + print_xyz("> homeZ > current_position", current_position); + print_xyz("> homeZ > destination", destination); + } #endif line_to_destination(); @@ -2430,8 +2518,10 @@ inline void gcode_G28() { } // !home_all_axes && homeZ - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("<<< Z_SAFE_HOMING"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("<<< Z_SAFE_HOMING"); + } #endif #else // !Z_SAFE_HOMING @@ -2440,8 +2530,10 @@ inline void gcode_G28() { #endif // !Z_SAFE_HOMING - #ifdef DEBUG_LEVELING - print_xyz("> (home_all_axis || homeZ) > final", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> (home_all_axis || homeZ) > final", current_position); + } #endif } // home_all_axis || homeZ @@ -2457,8 +2549,10 @@ inline void gcode_G28() { #endif #if ENABLED(ENDSTOPS_ONLY_FOR_HOMING) - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("ENDSTOPS_ONLY_FOR_HOMING enable_endstops(false)"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("ENDSTOPS_ONLY_FOR_HOMING enable_endstops(false)"); + } #endif enable_endstops(false); #endif @@ -2475,8 +2569,10 @@ inline void gcode_G28() { current_position[Z_AXIS] = MESH_HOME_SEARCH_Z; sync_plan_position(); mbl.active = 1; - #ifdef DEBUG_LEVELING - print_xyz("mbl_was_active > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("mbl_was_active > current_position", current_position); + } #endif } #endif @@ -2486,8 +2582,10 @@ inline void gcode_G28() { refresh_cmd_timeout(); endstops_hit_on_purpose(); // clear endstop hit flags - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("<<< gcode_G28"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("<<< gcode_G28"); + } #endif } @@ -2513,7 +2611,7 @@ inline void gcode_G28() { * | * | * v Y-axis - * + * */ inline void gcode_G29() { @@ -2640,7 +2738,7 @@ inline void gcode_G28() { * Will fail if the printer has not been homed with G28. * * Enhanced G29 Auto Bed Leveling Probe Routine - * + * * Parameters With AUTO_BED_LEVELING_GRID: * * P Set the size of the grid that will be probed (P x P points). @@ -2675,8 +2773,10 @@ inline void gcode_G28() { */ inline void gcode_G29() { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("gcode_G29 >>>"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("gcode_G29 >>>"); + } #endif // Don't allow auto-leveling without homing first @@ -2838,15 +2938,19 @@ inline void gcode_G28() { z_before = probePointCounter ? Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS] : Z_RAISE_BEFORE_PROBING; if (probePointCounter) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("z_before = (between) ", (float)(Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS])); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("z_before = (between) ", (float)(Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS])); + SERIAL_EOL; + } #endif } else { - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("z_before = (before) ", (float)Z_RAISE_BEFORE_PROBING); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("z_before = (before) ", (float)Z_RAISE_BEFORE_PROBING); + SERIAL_EOL; + } #endif } @@ -2887,8 +2991,10 @@ inline void gcode_G28() { } //xProbe } //yProbe - #ifdef DEBUG_LEVELING - print_xyz("> probing complete > current_position", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> probing complete > current_position", current_position); + } #endif clean_up_after_endstop_move(); @@ -2987,8 +3093,10 @@ inline void gcode_G28() { #else // !AUTO_BED_LEVELING_GRID - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("> 3-point Leveling"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("> 3-point Leveling"); + } #endif // Actions for each probe @@ -3020,11 +3128,13 @@ inline void gcode_G28() { z_tmp = current_position[Z_AXIS], real_z = st_get_position_mm(Z_AXIS); //get the real Z (since plan_get_position is now correcting the plane) - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > z_tmp = ", z_tmp); - SERIAL_EOL; - SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > real_z = ", real_z); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > z_tmp = ", z_tmp); + SERIAL_EOL; + SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > real_z = ", real_z); + SERIAL_EOL; + } #endif apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); // Apply the correction sending the Z probe offset @@ -3045,9 +3155,11 @@ inline void gcode_G28() { // adjust for inaccurate endstops, not for reasonably accurate probes. If it were // added here, it could be seen as a compensating factor for the Z probe. // - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("> AFTER apply_rotation_xyz > z_tmp = ", z_tmp); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("> AFTER apply_rotation_xyz > z_tmp = ", z_tmp); + SERIAL_EOL; + } #endif current_position[Z_AXIS] = -zprobe_zoffset + (z_tmp - real_z) @@ -3058,8 +3170,10 @@ inline void gcode_G28() { // current_position[Z_AXIS] += home_offset[Z_AXIS]; // The Z probe determines Z=0, not "Z home" sync_plan_position(); - #ifdef DEBUG_LEVELING - print_xyz("> corrected Z in G29", current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + print_xyz("> corrected Z in G29", current_position); + } #endif } #endif // !DELTA @@ -3071,16 +3185,20 @@ inline void gcode_G28() { #endif #ifdef Z_PROBE_END_SCRIPT - #ifdef DEBUG_LEVELING - SERIAL_ECHO("Z Probe End Script: "); - SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHO("Z Probe End Script: "); + SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT); + } #endif enqueuecommands_P(PSTR(Z_PROBE_END_SCRIPT)); st_synchronize(); #endif - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("<<< gcode_G29"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("<<< gcode_G29"); + } #endif } @@ -3420,7 +3538,7 @@ inline void gcode_M42() { * V = Verbose level (0-4, default=1) * E = Engage Z probe for each reading * L = Number of legs of movement before probe - * + * * This function assumes the bed has been homed. Specifically, that a G28 command * as been issued prior to invoking the M48 Z probe repeatability measurement function. * Any information generated by a prior G29 Bed leveling command will be lost and need to be @@ -3495,7 +3613,7 @@ inline void gcode_M42() { // // Now get everything to the specified probe point So we can safely do a probe to - // get us close to the bed. If the Z-Axis is far from the bed, we don't want to + // get us close to the bed. If the Z-Axis is far from the bed, we don't want to // use that as a starting point for each probe. // if (verbose_level > 2) @@ -3512,7 +3630,7 @@ inline void gcode_M42() { current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS); current_position[E_AXIS] = E_current = st_get_position_mm(E_AXIS); - // + // // OK, do the initial probe to get us close to the bed. // Then retrace the right amount and use that in subsequent probes // @@ -3576,7 +3694,7 @@ inline void gcode_M42() { } // n_legs if (deploy_probe_for_each_reading) { - deploy_z_probe(); + deploy_z_probe(); delay(1000); } @@ -3848,7 +3966,7 @@ inline void gcode_M109() { setTargetBed(code_value()); millis_t temp_ms = millis(); - + cancel_heatup = false; target_direction = isHeatingBed(); // true if heating, false if cooling @@ -3878,7 +3996,7 @@ inline void gcode_M109() { */ inline void gcode_M111() { marlin_debug_flags = code_seen('S') ? code_value_short() : DEBUG_INFO|DEBUG_COMMUNICATION; - + if (marlin_debug_flags & DEBUG_ECHO) { SERIAL_ECHO_START; SERIAL_ECHOLNPGM(MSG_DEBUG_ECHO); @@ -3891,6 +4009,12 @@ inline void gcode_M111() { SERIAL_ECHOLNPGM(MSG_DEBUG_DRYRUN); disable_all_heaters(); } +#if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM(MSG_DEBUG_LEVELING); + } +#endif } /** @@ -4136,13 +4260,13 @@ inline void gcode_M114() { SERIAL_PROTOCOLPGM(" Psi+Theta:"); SERIAL_PROTOCOL(delta[Y_AXIS]); SERIAL_EOL; - + SERIAL_PROTOCOLPGM("SCARA Cal - Theta:"); SERIAL_PROTOCOL(delta[X_AXIS]+home_offset[X_AXIS]); SERIAL_PROTOCOLPGM(" Psi+Theta (90):"); SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+home_offset[Y_AXIS]); SERIAL_EOL; - + SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:"); SERIAL_PROTOCOL(delta[X_AXIS]/90*axis_steps_per_unit[X_AXIS]); SERIAL_PROTOCOLPGM(" Psi+Theta:"); @@ -4322,7 +4446,7 @@ inline void gcode_M204() { SERIAL_ECHOPAIR("Setting Travel Acceleration: ", travel_acceleration ); SERIAL_EOL; } - + } /** @@ -4377,22 +4501,28 @@ inline void gcode_M206() { * M666: Set delta endstop adjustment */ inline void gcode_M666() { - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM(">>> gcode_M666"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM(">>> gcode_M666"); + } #endif for (int8_t i = X_AXIS; i <= Z_AXIS; i++) { if (code_seen(axis_codes[i])) { endstop_adj[i] = code_value(); - #ifdef DEBUG_LEVELING - SERIAL_ECHOPGM("endstop_adj["); - SERIAL_ECHO(axis_codes[i]); - SERIAL_ECHOPAIR("] = ", endstop_adj[i]); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPGM("endstop_adj["); + SERIAL_ECHO(axis_codes[i]); + SERIAL_ECHOPAIR("] = ", endstop_adj[i]); + SERIAL_EOL; + } #endif } } - #ifdef DEBUG_LEVELING - SERIAL_ECHOLNPGM("<<< gcode_M666"); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOLNPGM("<<< gcode_M666"); + } #endif } #elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS) @@ -4404,7 +4534,7 @@ inline void gcode_M206() { SERIAL_ECHOPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj); SERIAL_EOL; } - + #endif // !DELTA && Z_DUAL_ENDSTOPS #if ENABLED(FWRETRACT) @@ -4576,7 +4706,7 @@ inline void gcode_M226() { int servo_position = 0; if (code_seen('S')) { servo_position = code_value_short(); - if (servo_index >= 0 && servo_index < NUM_SERVOS) + if (servo_index >= 0 && servo_index < NUM_SERVOS) servo[servo_index].move(servo_position); else { SERIAL_ECHO_START; @@ -4628,7 +4758,7 @@ inline void gcode_M226() { if (code_seen('D')) PID_PARAM(Kd, e) = scalePID_d(code_value()); #if ENABLED(PID_ADD_EXTRUSION_RATE) if (code_seen('C')) PID_PARAM(Kc, e) = code_value(); - #endif + #endif updatePID(); SERIAL_PROTOCOL(MSG_OK); @@ -4647,7 +4777,7 @@ inline void gcode_M226() { //Kc does not have scaling applied above, or in resetting defaults SERIAL_PROTOCOL(PID_PARAM(Kc, e)); #endif - SERIAL_EOL; + SERIAL_EOL; } else { SERIAL_ECHO_START; @@ -4685,7 +4815,7 @@ inline void gcode_M226() { */ inline void gcode_M240() { #ifdef CHDK - + OUT_WRITE(CHDK, HIGH); chdkHigh = millis(); chdkActive = true; @@ -4919,7 +5049,7 @@ inline void gcode_M400() { st_synchronize(); } } #endif } - + /** * M405: Turn on filament sensor for control */ @@ -4948,13 +5078,13 @@ inline void gcode_M400() { st_synchronize(); } * M406: Turn off filament sensor for control */ inline void gcode_M406() { filament_sensor = false; } - + /** * M407: Get measured filament diameter on serial output */ inline void gcode_M407() { - SERIAL_PROTOCOLPGM("Filament dia (measured mm):"); - SERIAL_PROTOCOLLN(filament_width_meas); + SERIAL_PROTOCOLPGM("Filament dia (measured mm):"); + SERIAL_PROTOCOLLN(filament_width_meas); } #endif // FILAMENT_SENSOR @@ -5222,7 +5352,7 @@ inline void gcode_M503() { current_position[E_AXIS] = 0; st_synchronize(); #endif - + //return to normal if (code_seen('L')) destination[E_AXIS] -= code_value(); #ifdef FILAMENTCHANGE_FINALRETRACT @@ -5250,12 +5380,12 @@ inline void gcode_M503() { line_to_destination(); destination[E_AXIS] = lastpos[E_AXIS]; line_to_destination(); - #endif + #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) filrunoutEnqueued = false; #endif - + } #endif // FILAMENTCHANGEENABLE @@ -6084,21 +6214,23 @@ void ok_to_send() { SERIAL_PROTOCOLPGM(" P"); SERIAL_PROTOCOL(int(BLOCK_BUFFER_SIZE - movesplanned() - 1)); SERIAL_PROTOCOLPGM(" B"); SERIAL_PROTOCOL(BUFSIZE - commands_in_queue); #endif - SERIAL_EOL; + SERIAL_EOL; } void clamp_to_software_endstops(float target[3]) { if (min_software_endstops) { NOLESS(target[X_AXIS], min_pos[X_AXIS]); NOLESS(target[Y_AXIS], min_pos[Y_AXIS]); - + float negative_z_offset = 0; #if ENABLED(AUTO_BED_LEVELING_FEATURE) if (zprobe_zoffset < 0) negative_z_offset += zprobe_zoffset; if (home_offset[Z_AXIS] < 0) { - #ifdef DEBUG_LEVELING - SERIAL_ECHOPAIR("> clamp_to_software_endstops > Add home_offset[Z_AXIS]:", home_offset[Z_AXIS]); - SERIAL_EOL; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (marlin_debug_flags & DEBUG_LEVELING) { + SERIAL_ECHOPAIR("> clamp_to_software_endstops > Add home_offset[Z_AXIS]:", home_offset[Z_AXIS]); + SERIAL_EOL; + } #endif negative_z_offset += home_offset[Z_AXIS]; } @@ -6444,54 +6576,54 @@ void plan_arc( r_axis1 = -offset[Y_AXIS], rt_axis0 = target[X_AXIS] - center_axis0, rt_axis1 = target[Y_AXIS] - center_axis1; - + // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1); if (angular_travel < 0) { angular_travel += RADIANS(360); } if (clockwise) { angular_travel -= RADIANS(360); } - + // Make a circle if the angular rotation is 0 if (current_position[X_AXIS] == target[X_AXIS] && current_position[Y_AXIS] == target[Y_AXIS] && angular_travel == 0) angular_travel += RADIANS(360); - + float mm_of_travel = hypot(angular_travel*radius, fabs(linear_travel)); if (mm_of_travel < 0.001) { return; } uint16_t segments = floor(mm_of_travel / MM_PER_ARC_SEGMENT); if (segments == 0) segments = 1; - + float theta_per_segment = angular_travel/segments; float linear_per_segment = linear_travel/segments; float extruder_per_segment = extruder_travel/segments; - + /* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, and phi is the angle of rotation. Based on the solution approach by Jens Geisler. r_T = [cos(phi) -sin(phi); sin(phi) cos(phi] * r ; - - For arc generation, the center of the circle is the axis of rotation and the radius vector is + + For arc generation, the center of the circle is the axis of rotation and the radius vector is defined from the circle center to the initial position. Each line segment is formed by successive vector rotations. This requires only two cos() and sin() computations to form the rotation matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since all double numbers are single precision on the Arduino. (True double precision will not have round off issues for CNC applications.) Single precision error can accumulate to be greater than - tool precision in some cases. Therefore, arc path correction is implemented. + tool precision in some cases. Therefore, arc path correction is implemented. Small angle approximation may be used to reduce computation overhead further. This approximation holds for everything, but very small circles and large MM_PER_ARC_SEGMENT values. In other words, theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large - to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for + to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an issue for CNC machines with the single precision Arduino calculations. - - This approximation also allows plan_arc to immediately insert a line segment into the planner + + This approximation also allows plan_arc to immediately insert a line segment into the planner without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied - a correction, the planner should have caught up to the lag caused by the initial plan_arc overhead. - This is important when there are successive arc motions. + a correction, the planner should have caught up to the lag caused by the initial plan_arc overhead. + This is important when there are successive arc motions. */ // Vector rotation matrix values float cos_T = 1-0.5*theta_per_segment*theta_per_segment; // Small angle approximation float sin_T = theta_per_segment; - + float arc_target[NUM_AXIS]; float sin_Ti; float cos_Ti; @@ -6501,7 +6633,7 @@ void plan_arc( // Initialize the linear axis arc_target[Z_AXIS] = current_position[Z_AXIS]; - + // Initialize the extruder axis arc_target[E_AXIS] = current_position[E_AXIS]; @@ -6622,49 +6754,49 @@ void plan_arc( //SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]); //SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]); - } + } void calculate_delta(float cartesian[3]){ //reverse kinematics. // Perform reversed kinematics, and place results in delta[3] // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014 - + float SCARA_pos[2]; - static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi; - + static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi; + SCARA_pos[X_AXIS] = cartesian[X_AXIS] * axis_scaling[X_AXIS] - SCARA_offset_x; //Translate SCARA to standard X Y SCARA_pos[Y_AXIS] = cartesian[Y_AXIS] * axis_scaling[Y_AXIS] - SCARA_offset_y; // With scaling factor. - + #if (Linkage_1 == Linkage_2) SCARA_C2 = ( ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) ) / (2 * (float)L1_2) ) - 1; #else - SCARA_C2 = ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2 ) / 45000; + SCARA_C2 = ( sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2 ) / 45000; #endif - + SCARA_S2 = sqrt( 1 - sq(SCARA_C2) ); - + SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2; SCARA_K2 = Linkage_2 * SCARA_S2; - + SCARA_theta = ( atan2(SCARA_pos[X_AXIS],SCARA_pos[Y_AXIS])-atan2(SCARA_K1, SCARA_K2) ) * -1; SCARA_psi = atan2(SCARA_S2,SCARA_C2); - + delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG; // Multiply by 180/Pi - theta is support arm angle delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG; // - equal to sub arm angle (inverted motor) delta[Z_AXIS] = cartesian[Z_AXIS]; - + /* SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]); SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]); SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]); - + SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]); SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]); - + SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]); SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]); SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]); - + SERIAL_ECHOPGM("C2="); SERIAL_ECHO(SCARA_C2); SERIAL_ECHOPGM(" S2="); SERIAL_ECHO(SCARA_S2); SERIAL_ECHOPGM(" Theta="); SERIAL_ECHO(SCARA_theta); @@ -6742,7 +6874,7 @@ void idle() { * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) */ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { - + #if HAS_FILRUNOUT if (IS_SD_PRINTING && !(READ(FILRUNOUT_PIN) ^ FIL_RUNOUT_INVERTING)) filrunout(); @@ -6781,7 +6913,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { #endif #if HAS_KILL - + // Check if the kill button was pressed and wait just in case it was an accidental // key kill key press // ------------------------------------------------------------------------------- @@ -6814,7 +6946,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { homeDebounceCount = 0; } #endif - + #if HAS_CONTROLLERFAN controllerFan(); // Check if fan should be turned on to cool stepper drivers down #endif @@ -6911,7 +7043,7 @@ void kill(const char *lcd_msg) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_KILLED); - + // FMC small patch to update the LCD before ending sei(); // enable interrupts for (int i = 5; i--; lcd_update()) delay(200); // Wait a short time diff --git a/Marlin/language.h b/Marlin/language.h index 53e8b3077..791dd8d6d 100644 --- a/Marlin/language.h +++ b/Marlin/language.h @@ -214,6 +214,7 @@ #define MSG_DEBUG_INFO "DEBUG INFO ENABLED" #define MSG_DEBUG_ERRORS "DEBUG ERRORS ENABLED" #define MSG_DEBUG_DRYRUN "DEBUG DRYRUN ENABLED" +#define MSG_DEBUG_LEVELING "DEBUG LEVELING ENABLED" // LCD Menu Messages