From 581b2aae043bd0c1c9e13d003739756e6305b001 Mon Sep 17 00:00:00 2001 From: Wurstnase Date: Fri, 3 Apr 2015 16:11:32 +0200 Subject: [PATCH 1/7] fix feedrate for homing z max_feedrate is in mm/s. line_to_destination needs a feedrate in mm/min because there is feedrate/60. --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6b41be617..daa78b40d 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1950,7 +1950,7 @@ inline void gcode_G28() { current_position[Z_AXIS] = 0; plan_set_position(cpx, cpy, 0, current_position[E_AXIS]); destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); // Set destination away from bed - feedrate = max_feedrate[Z_AXIS]; + feedrate = max_feedrate[Z_AXIS] * 60; // max_feedrate is in mm/s. line_to_destination is feedrate/60. line_to_destination(); st_synchronize(); HOMEAXIS(Z); From 45565b680dce05481d4510c61e12c61b15a21457 Mon Sep 17 00:00:00 2001 From: Wurstnase Date: Fri, 3 Apr 2015 18:01:28 +0200 Subject: [PATCH 2/7] second wrong feedrate --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index daa78b40d..266812581 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1817,7 +1817,7 @@ inline void gcode_G28() { // Raise Z before homing any other axes if (home_all_axis || homeZ) { destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); // Set destination away from bed - feedrate = max_feedrate[Z_AXIS]; + feedrate = max_feedrate[Z_AXIS] * 60; line_to_destination(); st_synchronize(); } From 0e8182bbf2f0ac2c3340b7d89e6b77fa2f55f292 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Apr 2015 15:31:35 -0700 Subject: [PATCH 3/7] Additional pin tests, cleanup --- Marlin/Conditionals.h | 93 ++- Marlin/Configuration.h | 4 +- Marlin/ConfigurationStore.cpp | 4 +- Marlin/Configuration_adv.h | 6 +- Marlin/Marlin.h | 18 +- Marlin/Marlin_main.cpp | 784 +++++++++--------- Marlin/SanityCheck.h | 24 +- Marlin/configurator/config/Configuration.h | 2 +- .../configurator/config/Configuration_adv.h | 6 +- Marlin/dogm_lcd_implementation.h | 2 +- .../Felix/Configuration.h | 2 +- .../Felix/Configuration_DUAL.h | 2 +- .../Felix/Configuration_adv.h | 6 +- .../Hephestos/Configuration.h | 2 +- .../Hephestos/Configuration_adv.h | 6 +- .../K8200/Configuration.h | 2 +- .../K8200/Configuration_adv.h | 6 +- .../SCARA/Configuration.h | 2 +- .../SCARA/Configuration_adv.h | 6 +- .../WITBOX/Configuration.h | 2 +- .../WITBOX/Configuration_adv.h | 6 +- .../delta/generic/Configuration.h | 10 +- .../delta/generic/Configuration_adv.h | 6 +- .../delta/kossel_mini/Configuration.h | 10 +- .../delta/kossel_mini/Configuration_adv.h | 6 +- .../makibox/Configuration.h | 2 +- .../makibox/Configuration_adv.h | 6 +- .../tvrrug/Round2/Configuration.h | 2 +- .../tvrrug/Round2/Configuration_adv.h | 6 +- Marlin/mesh_bed_leveling.h | 2 +- Marlin/planner.cpp | 10 +- Marlin/stepper.cpp | 116 +-- Marlin/temperature.h | 2 +- Marlin/ultralcd.h | 16 +- 34 files changed, 603 insertions(+), 576 deletions(-) diff --git a/Marlin/Conditionals.h b/Marlin/Conditionals.h index c7e208472..1093e7081 100644 --- a/Marlin/Conditionals.h +++ b/Marlin/Conditionals.h @@ -10,6 +10,8 @@ #ifndef CONFIGURATION_LCD // Get the LCD defines which are needed first + #define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0) + #define CONFIGURATION_LCD #if defined(MAKRPANEL) @@ -276,7 +278,7 @@ #define PS_ON_AWAKE HIGH #define PS_ON_ASLEEP LOW #endif - #define HAS_POWER_SWITCH (POWER_SUPPLY > 0 && defined(PS_ON_PIN) && PS_ON_PIN >= 0) + #define HAS_POWER_SWITCH (POWER_SUPPLY > 0 && PIN_EXISTS(PS_ON)) /** * Temp Sensor defines @@ -347,25 +349,80 @@ #endif /** - * Shorthand for pin tests, for temperature.cpp + * Shorthand for pin tests, used wherever needed */ - #define HAS_TEMP_0 (defined(TEMP_0_PIN) && TEMP_0_PIN >= 0 && TEMP_SENSOR_0 != 0 && TEMP_SENSOR_0 != -2) - #define HAS_TEMP_1 (defined(TEMP_1_PIN) && TEMP_1_PIN >= 0 && TEMP_SENSOR_1 != 0) - #define HAS_TEMP_2 (defined(TEMP_2_PIN) && TEMP_2_PIN >= 0 && TEMP_SENSOR_2 != 0) - #define HAS_TEMP_3 (defined(TEMP_3_PIN) && TEMP_3_PIN >= 0 && TEMP_SENSOR_3 != 0) - #define HAS_TEMP_BED (defined(TEMP_BED_PIN) && TEMP_BED_PIN >= 0 && TEMP_SENSOR_BED != 0) - #define HAS_FILAMENT_SENSOR (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) - #define HAS_HEATER_0 (defined(HEATER_0_PIN) && HEATER_0_PIN >= 0) - #define HAS_HEATER_1 (defined(HEATER_1_PIN) && HEATER_1_PIN >= 0) - #define HAS_HEATER_2 (defined(HEATER_2_PIN) && HEATER_2_PIN >= 0) - #define HAS_HEATER_3 (defined(HEATER_3_PIN) && HEATER_3_PIN >= 0) - #define HAS_HEATER_BED (defined(HEATER_BED_PIN) && HEATER_BED_PIN >= 0) - #define HAS_AUTO_FAN_0 (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN >= 0) - #define HAS_AUTO_FAN_1 (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN >= 0) - #define HAS_AUTO_FAN_2 (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN >= 0) - #define HAS_AUTO_FAN_3 (defined(EXTRUDER_3_AUTO_FAN_PIN) && EXTRUDER_3_AUTO_FAN_PIN >= 0) + #define HAS_TEMP_0 (PIN_EXISTS(TEMP_0) && TEMP_SENSOR_0 != 0 && TEMP_SENSOR_0 != -2) + #define HAS_TEMP_1 (PIN_EXISTS(TEMP_1) && TEMP_SENSOR_1 != 0) + #define HAS_TEMP_2 (PIN_EXISTS(TEMP_2) && TEMP_SENSOR_2 != 0) + #define HAS_TEMP_3 (PIN_EXISTS(TEMP_3) && TEMP_SENSOR_3 != 0) + #define HAS_TEMP_BED (PIN_EXISTS(TEMP_BED) && TEMP_SENSOR_BED != 0) + #define HAS_HEATER_0 (PIN_EXISTS(HEATER_0)) + #define HAS_HEATER_1 (PIN_EXISTS(HEATER_1)) + #define HAS_HEATER_2 (PIN_EXISTS(HEATER_2)) + #define HAS_HEATER_3 (PIN_EXISTS(HEATER_3)) + #define HAS_HEATER_BED (PIN_EXISTS(HEATER_BED)) + #define HAS_AUTO_FAN_0 (PIN_EXISTS(EXTRUDER_0_AUTO_FAN)) + #define HAS_AUTO_FAN_1 (PIN_EXISTS(EXTRUDER_1_AUTO_FAN)) + #define HAS_AUTO_FAN_2 (PIN_EXISTS(EXTRUDER_2_AUTO_FAN)) + #define HAS_AUTO_FAN_3 (PIN_EXISTS(EXTRUDER_3_AUTO_FAN)) #define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3) - #define HAS_FAN (defined(FAN_PIN) && FAN_PIN >= 0) + #define HAS_FAN (PIN_EXISTS(FAN)) + #define HAS_CONTROLLERFAN (PIN_EXISTS(CONTROLLERFAN)) + #define HAS_SERVO_0 (PIN_EXISTS(SERVO0)) + #define HAS_SERVO_1 (PIN_EXISTS(SERVO1)) + #define HAS_SERVO_2 (PIN_EXISTS(SERVO2)) + #define HAS_SERVO_3 (PIN_EXISTS(SERVO3)) + #define HAS_FILAMENT_SENSOR (defined(FILAMENT_SENSOR) && PIN_EXISTS(FILWIDTH)) + #define HAS_FILRUNOUT (PIN_EXISTS(FILRUNOUT)) + #define HAS_HOME (PIN_EXISTS(HOME)) + #define HAS_KILL (PIN_EXISTS(KILL)) + #define HAS_SUICIDE (PIN_EXISTS(SUICIDE)) + #define HAS_PHOTOGRAPH (PIN_EXISTS(PHOTOGRAPH)) + #define HAS_X_MIN (PIN_EXISTS(X_MIN)) + #define HAS_X_MAX (PIN_EXISTS(X_MAX)) + #define HAS_Y_MIN (PIN_EXISTS(Y_MIN)) + #define HAS_Y_MAX (PIN_EXISTS(Y_MAX)) + #define HAS_Z_MIN (PIN_EXISTS(Z_MIN)) + #define HAS_Z_MAX (PIN_EXISTS(Z_MAX)) + #define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN)) + #define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX)) + #define HAS_SOLENOID_1 (PIN_EXISTS(SOL1)) + #define HAS_SOLENOID_2 (PIN_EXISTS(SOL2)) + #define HAS_SOLENOID_3 (PIN_EXISTS(SOL3)) + #define HAS_MICROSTEPS (PIN_EXISTS(X_MS1)) + #define HAS_MICROSTEPS_E0 (PIN_EXISTS(E0_MS1)) + #define HAS_MICROSTEPS_E1 (PIN_EXISTS(E1_MS1)) + #define HAS_MICROSTEPS_E2 (PIN_EXISTS(E2_MS1)) + #define HAS_X_ENABLE (PIN_EXISTS(X_ENABLE)) + #define HAS_X2_ENABLE (PIN_EXISTS(X2_ENABLE)) + #define HAS_Y_ENABLE (PIN_EXISTS(Y_ENABLE)) + #define HAS_Y2_ENABLE (PIN_EXISTS(Y2_ENABLE)) + #define HAS_Z_ENABLE (PIN_EXISTS(Z_ENABLE)) + #define HAS_Z2_ENABLE (PIN_EXISTS(Z2_ENABLE)) + #define HAS_E0_ENABLE (PIN_EXISTS(E0_ENABLE)) + #define HAS_E1_ENABLE (PIN_EXISTS(E1_ENABLE)) + #define HAS_E2_ENABLE (PIN_EXISTS(E2_ENABLE)) + #define HAS_E3_ENABLE (PIN_EXISTS(E3_ENABLE)) + #define HAS_X_DIR (PIN_EXISTS(X_DIR)) + #define HAS_X2_DIR (PIN_EXISTS(X2_DIR)) + #define HAS_Y_DIR (PIN_EXISTS(Y_DIR)) + #define HAS_Y2_DIR (PIN_EXISTS(Y2_DIR)) + #define HAS_Z_DIR (PIN_EXISTS(Z_DIR)) + #define HAS_Z2_DIR (PIN_EXISTS(Z2_DIR)) + #define HAS_E0_DIR (PIN_EXISTS(E0_DIR)) + #define HAS_E1_DIR (PIN_EXISTS(E1_DIR)) + #define HAS_E2_DIR (PIN_EXISTS(E2_DIR)) + #define HAS_E3_DIR (PIN_EXISTS(E3_DIR)) + #define HAS_X_STEP (PIN_EXISTS(X_STEP)) + #define HAS_X2_STEP (PIN_EXISTS(X2_STEP)) + #define HAS_Y_STEP (PIN_EXISTS(Y_STEP)) + #define HAS_Y2_STEP (PIN_EXISTS(Y2_STEP)) + #define HAS_Z_STEP (PIN_EXISTS(Z_STEP)) + #define HAS_Z2_STEP (PIN_EXISTS(Z2_STEP)) + #define HAS_E0_STEP (PIN_EXISTS(E0_STEP)) + #define HAS_E1_STEP (PIN_EXISTS(E1_STEP)) + #define HAS_E2_STEP (PIN_EXISTS(E2_STEP)) + #define HAS_E3_STEP (PIN_EXISTS(E3_STEP)) /** * Helper Macros for heaters and extruder fan diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index a984923ea..748a3914c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -387,7 +387,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 @@ -670,7 +670,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o // Data from: http://www.doc-diy.net/photo/rc-1_hacked/ // #define PHOTOGRAPH_PIN 23 -// SF send wrong arc g-codes when using Arc Point as fillet procedure +// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure //#define SF_ARC_FIX // Support for the BariCUDA Paste Extruder. diff --git a/Marlin/ConfigurationStore.cpp b/Marlin/ConfigurationStore.cpp index b1da94a30..f82e83fc4 100644 --- a/Marlin/ConfigurationStore.cpp +++ b/Marlin/ConfigurationStore.cpp @@ -78,7 +78,7 @@ #include "ultralcd.h" #include "ConfigurationStore.h" -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #include "mesh_bed_leveling.h" #endif // MESH_BED_LEVELING @@ -308,7 +308,7 @@ void Config_RetrieveSettings() { uint8_t mesh_num_x = 0; uint8_t mesh_num_y = 0; - #if defined(MESH_BED_LEVELING) + #ifdef MESH_BED_LEVELING EEPROM_READ_VAR(i, mbl.active); EEPROM_READ_VAR(i, mesh_num_x); EEPROM_READ_VAR(i, mesh_num_y); diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d689ac47f..4ed188946 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 2 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 2 #define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index e0441714b..1f295a65a 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -110,11 +110,10 @@ void process_commands(); void manage_inactivity(bool ignore_stepper_queue=false); -#if defined(DUAL_X_CARRIAGE) && defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1 \ - && defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1 +#if defined(DUAL_X_CARRIAGE) && HAS_X_ENABLE && HAS_X2_ENABLE #define enable_x() do { X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); } while (0) #define disable_x() do { X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0) -#elif defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1 +#elif HAS_X_ENABLE #define enable_x() X_ENABLE_WRITE( X_ENABLE_ON) #define disable_x() { X_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } #else @@ -122,7 +121,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_x() ; #endif -#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1 +#if HAS_Y_ENABLE #ifdef Y_DUAL_STEPPER_DRIVERS #define enable_y() { Y_ENABLE_WRITE( Y_ENABLE_ON); Y2_ENABLE_WRITE(Y_ENABLE_ON); } #define disable_y() { Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; } @@ -135,7 +134,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_y() ; #endif -#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1 +#if HAS_Z_ENABLE #ifdef Z_DUAL_STEPPER_DRIVERS #define enable_z() { Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); } #define disable_z() { Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } @@ -148,7 +147,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_z() ; #endif -#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1) +#if HAS_E0_ENABLE #define enable_e0() E0_ENABLE_WRITE(E_ENABLE_ON) #define disable_e0() E0_ENABLE_WRITE(!E_ENABLE_ON) #else @@ -156,7 +155,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_e0() /* nothing */ #endif -#if (EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1) +#if (EXTRUDERS > 1) && HAS_E1_ENABLE #define enable_e1() E1_ENABLE_WRITE(E_ENABLE_ON) #define disable_e1() E1_ENABLE_WRITE(!E_ENABLE_ON) #else @@ -164,7 +163,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_e1() /* nothing */ #endif -#if (EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1) +#if (EXTRUDERS > 2) && HAS_E2_ENABLE #define enable_e2() E2_ENABLE_WRITE(E_ENABLE_ON) #define disable_e2() E2_ENABLE_WRITE(!E_ENABLE_ON) #else @@ -172,7 +171,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_e2() /* nothing */ #endif -#if (EXTRUDERS > 3) && defined(E3_ENABLE_PIN) && (E3_ENABLE_PIN > -1) +#if (EXTRUDERS > 3) && HAS_E3_ENABLE #define enable_e3() E3_ENABLE_WRITE(E_ENABLE_ON) #define disable_e3() E3_ENABLE_WRITE(!E_ENABLE_ON) #else @@ -194,7 +193,6 @@ void get_coordinates(); void adjust_delta(float cartesian[3]); #endif extern float delta[3]; - void prepare_move_raw(); #endif #ifdef SCARA void calculate_delta(float cartesian[3]); diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6b41be617..13484c986 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -36,11 +36,11 @@ #endif #endif // ENABLE_AUTO_BED_LEVELING -#define SERVO_LEVELING defined(ENABLE_AUTO_BED_LEVELING) && PROBE_SERVO_DEACTIVATION_DELAY > 0 +#define SERVO_LEVELING (defined(ENABLE_AUTO_BED_LEVELING) && PROBE_SERVO_DEACTIVATION_DELAY > 0) -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #include "mesh_bed_leveling.h" -#endif // MESH_BED_LEVELING +#endif #include "ultralcd.h" #include "planner.h" @@ -298,6 +298,7 @@ int fanSpeed = 0; float delta_diagonal_rod_2 = sq(delta_diagonal_rod); float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; #ifdef ENABLE_AUTO_BED_LEVELING + int delta_grid_spacing[2] = { 0, 0 }; float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS]; #endif #endif @@ -422,26 +423,24 @@ void serial_echopair_P(const char *s_P, unsigned long v) //Injects the next command from the pending sequence of commands, when possible //Return false if and only if no command was pending -static bool drain_queued_commands_P() -{ - char cmd[30]; - if(!queued_commands_P) - return false; +static bool drain_queued_commands_P() { + if (!queued_commands_P) return false; + // Get the next 30 chars from the sequence of gcodes to run - strncpy_P(cmd, queued_commands_P, sizeof(cmd)-1); - cmd[sizeof(cmd)-1]= 0; + char cmd[30]; + strncpy_P(cmd, queued_commands_P, sizeof(cmd) - 1); + cmd[sizeof(cmd) - 1] = '\0'; + // Look for the end of line, or the end of sequence - size_t i= 0; + size_t i = 0; char c; - while( (c= cmd[i]) && c!='\n' ) - ++i; // look for the end of this gcode command - cmd[i]= 0; - if(enquecommand(cmd)) // buffer was not full (else we will retry later) - { - if(c) - queued_commands_P+= i+1; // move to next command + while((c = cmd[i]) && c != '\n') i++; // find the end of this gcode command + cmd[i] = '\0'; + if (enquecommand(cmd)) { // buffer was not full (else we will retry later) + if (c) + queued_commands_P += i + 1; // move to next command else - queued_commands_P= NULL; // will have no more commands in the sequence + queued_commands_P = NULL; // will have no more commands in the sequence } return true; } @@ -449,10 +448,9 @@ static bool drain_queued_commands_P() //Record one or many commands to run from program memory. //Aborts the current queue, if any. //Note: drain_queued_commands_P() must be called repeatedly to drain the commands afterwards -void enquecommands_P(const char* pgcode) -{ - queued_commands_P= pgcode; - drain_queued_commands_P(); // first command exectuted asap (when possible) +void enquecommands_P(const char* pgcode) { + queued_commands_P = pgcode; + drain_queued_commands_P(); // first command executed asap (when possible) } //adds a single command to the main command buffer, from RAM @@ -478,42 +476,42 @@ bool enquecommand(const char *cmd) void setup_killpin() { - #if defined(KILL_PIN) && KILL_PIN > -1 + #if HAS_KILL SET_INPUT(KILL_PIN); - WRITE(KILL_PIN,HIGH); + WRITE(KILL_PIN, HIGH); #endif } void setup_filrunoutpin() { -#if defined(FILRUNOUT_PIN) && FILRUNOUT_PIN > -1 - pinMode(FILRUNOUT_PIN,INPUT); - #if defined(ENDSTOPPULLUP_FIL_RUNOUT) - WRITE(FILLRUNOUT_PIN,HIGH); - #endif -#endif + #if HAS_FILRUNOUT + pinMode(FILRUNOUT_PIN, INPUT); + #ifdef ENDSTOPPULLUP_FIL_RUNOUT + WRITE(FILLRUNOUT_PIN, HIGH); + #endif + #endif } // Set home pin void setup_homepin(void) { -#if defined(HOME_PIN) && HOME_PIN > -1 - SET_INPUT(HOME_PIN); - WRITE(HOME_PIN,HIGH); -#endif + #if HAS_HOME + SET_INPUT(HOME_PIN); + WRITE(HOME_PIN, HIGH); + #endif } void setup_photpin() { - #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1 + #if HAS_PHOTOGRAPH OUT_WRITE(PHOTOGRAPH_PIN, LOW); #endif } void setup_powerhold() { - #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1 + #if HAS_SUICIDE OUT_WRITE(SUICIDE_PIN, HIGH); #endif #if HAS_POWER_SWITCH @@ -527,37 +525,31 @@ void setup_powerhold() void suicide() { - #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1 + #if HAS_SUICIDE OUT_WRITE(SUICIDE_PIN, LOW); #endif } void servo_init() { - #if (NUM_SERVOS >= 1) && defined(SERVO0_PIN) && (SERVO0_PIN > -1) + #if NUM_SERVOS >= 1 && HAS_SERVO_0 servos[0].attach(SERVO0_PIN); #endif - #if (NUM_SERVOS >= 2) && defined(SERVO1_PIN) && (SERVO1_PIN > -1) + #if NUM_SERVOS >= 2 && HAS_SERVO_1 servos[1].attach(SERVO1_PIN); #endif - #if (NUM_SERVOS >= 3) && defined(SERVO2_PIN) && (SERVO2_PIN > -1) + #if NUM_SERVOS >= 3 && HAS_SERVO_2 servos[2].attach(SERVO2_PIN); #endif - #if (NUM_SERVOS >= 4) && defined(SERVO3_PIN) && (SERVO3_PIN > -1) + #if NUM_SERVOS >= 4 && HAS_SERVO_3 servos[3].attach(SERVO3_PIN); #endif - #if (NUM_SERVOS >= 5) - #error "TODO: enter initalisation code for more servos" - #endif // Set position of Servo Endstops that are defined #ifdef SERVO_ENDSTOPS - for(int8_t i = 0; i < 3; i++) - { - if(servo_endstops[i] > -1) { + for (int i = 0; i < 3; i++) + if (servo_endstops[i] >= 0) servos[servo_endstops[i]].write(servo_endstop_angles[i * 2 + 1]); - } - } #endif #if SERVO_LEVELING @@ -624,7 +616,7 @@ void setup() lcd_init(); _delay_ms(1000); // wait 1sec to display the splash screen - #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1 + #if HAS_CONTROLLERFAN SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan #endif @@ -648,47 +640,37 @@ void setup() } -void loop() -{ - if(buflen < (BUFSIZE-1)) - get_command(); +void loop() { + if (buflen < BUFSIZE - 1) get_command(); + #ifdef SDSUPPORT - card.checkautostart(false); + card.checkautostart(false); #endif - if(buflen) - { + + if (buflen) { #ifdef SDSUPPORT - if(card.saving) - { - if(strstr_P(cmdbuffer[bufindr], PSTR("M29")) == NULL) - { + if (card.saving) { + if (strstr_P(cmdbuffer[bufindr], PSTR("M29")) == NULL) { card.write_command(cmdbuffer[bufindr]); - if(card.logging) - { + if (card.logging) process_commands(); - } else - { SERIAL_PROTOCOLLNPGM(MSG_OK); - } } - else - { + else { card.closefile(); SERIAL_PROTOCOLLNPGM(MSG_FILE_SAVED); } } else - { process_commands(); - } #else process_commands(); - #endif //SDSUPPORT - buflen = (buflen-1); - bufindr = (bufindr + 1)%BUFSIZE; + #endif // SDSUPPORT + buflen--; + bufindr = (bufindr + 1) % BUFSIZE; } - //check heater every n milliseconds + // Check heater every n milliseconds manage_heater(); manage_inactivity(); checkHitEndstops(); @@ -697,7 +679,7 @@ void loop() void get_command() { - if(drain_queued_commands_P()) // priority is given to non-serial commands + if (drain_queued_commands_P()) // priority is given to non-serial commands return; while( MYSERIAL.available() > 0 && buflen < BUFSIZE) { @@ -916,7 +898,7 @@ XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS); XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS); XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS); XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH); -XYZ_CONSTS_FROM_CONFIG(float, home_retract_mm, HOME_RETRACT_MM); +XYZ_CONSTS_FROM_CONFIG(float, home_bump_mm, HOME_BUMP_MM); XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR); #ifdef DUAL_X_CARRIAGE @@ -1019,6 +1001,8 @@ static void axis_is_at_home(int axis) { #endif } +inline void refresh_cmd_timeout() { previous_millis_cmd = millis(); } + /** * Some planner shorthand inline functions */ @@ -1043,6 +1027,18 @@ inline void sync_plan_position() { #ifdef ENABLE_AUTO_BED_LEVELING + #ifdef DELTA + /** + * Calculate delta, start a line, and set current_position to destination + */ + void prepare_move_raw() { + refresh_cmd_timeout(); + calculate_delta(destination); + plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], (feedrate/60)*(feedmultiply/100.0), active_extruder); + for (int i = 0; i < NUM_AXIS; i++) current_position[i] = destination[i]; + } + #endif + #ifdef AUTO_BED_LEVELING_GRID #ifndef DELTA @@ -1132,7 +1128,7 @@ inline void sync_plan_position() { plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS]); // move up the retract distance - zPosition += home_retract_mm(Z_AXIS); + zPosition += home_bump_mm(Z_AXIS); line_to_z(zPosition); st_synchronize(); endstops_hit_on_purpose(); // clear endstop hit flags @@ -1145,7 +1141,7 @@ inline void sync_plan_position() { SERIAL_ECHOLN("Warning: The Homing Bump Feedrate Divisor cannot be less than 1"); } - zPosition -= home_retract_mm(Z_AXIS) * 2; + zPosition -= home_bump_mm(Z_AXIS) * 2; line_to_z(zPosition); st_synchronize(); endstops_hit_on_purpose(); // clear endstop hit flags @@ -1157,6 +1153,9 @@ inline void sync_plan_position() { #endif // !DELTA } + /** + * + */ static void do_blocking_move_to(float x, float y, float z) { float oldFeedRate = feedrate; @@ -1194,7 +1193,7 @@ inline void sync_plan_position() { saved_feedrate = feedrate; saved_feedmultiply = feedmultiply; feedmultiply = 100; - previous_millis_cmd = millis(); + refresh_cmd_timeout(); enable_endstops(true); } @@ -1204,10 +1203,10 @@ inline void sync_plan_position() { #endif feedrate = saved_feedrate; feedmultiply = saved_feedmultiply; - previous_millis_cmd = millis(); + refresh_cmd_timeout(); } - static void engage_z_probe() { + static void deploy_z_probe() { #ifdef SERVO_ENDSTOPS @@ -1259,7 +1258,7 @@ inline void sync_plan_position() { } - static void retract_z_probe() { + static void stow_z_probe() { #ifdef SERVO_ENDSTOPS @@ -1291,19 +1290,19 @@ inline void sync_plan_position() { prepare_move_raw(); // Move to the start position to initiate retraction - destination[X_AXIS] = Z_PROBE_ALLEN_KEY_RETRACT_X; - destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_RETRACT_Y; - destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_RETRACT_Z; + destination[X_AXIS] = Z_PROBE_ALLEN_KEY_STOW_X; + destination[Y_AXIS] = Z_PROBE_ALLEN_KEY_STOW_Y; + destination[Z_AXIS] = Z_PROBE_ALLEN_KEY_STOW_Z; prepare_move_raw(); // Move the nozzle down to push the probe into retracted position feedrate = homing_feedrate[Z_AXIS]/10; - destination[Z_AXIS] = current_position[Z_AXIS] - Z_PROBE_ALLEN_KEY_RETRACT_DEPTH; + destination[Z_AXIS] = current_position[Z_AXIS] - Z_PROBE_ALLEN_KEY_STOW_DEPTH; prepare_move_raw(); // Move up for safety feedrate = homing_feedrate[Z_AXIS]/2; - destination[Z_AXIS] = current_position[Z_AXIS] + Z_PROBE_ALLEN_KEY_RETRACT_DEPTH * 2; + destination[Z_AXIS] = current_position[Z_AXIS] + Z_PROBE_ALLEN_KEY_STOW_DEPTH * 2; prepare_move_raw(); // Home XY for safety @@ -1342,7 +1341,7 @@ inline void sync_plan_position() { do_blocking_move_to(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]); #if !defined(Z_PROBE_SLED) && !defined(Z_PROBE_ALLEN_KEY) - if (retract_action & ProbeEngage) engage_z_probe(); + if (retract_action & ProbeEngage) deploy_z_probe(); #endif run_z_probe(); @@ -1356,7 +1355,7 @@ inline void sync_plan_position() { #endif #if !defined(Z_PROBE_SLED) && !defined(Z_PROBE_ALLEN_KEY) - if (retract_action & ProbeRetract) retract_z_probe(); + if (retract_action & ProbeRetract) stow_z_probe(); #endif if (verbose_level > 2) { @@ -1460,10 +1459,10 @@ static void homeaxis(int axis) { sync_plan_position(); // Engage Servo endstop if enabled - #ifdef SERVO_ENDSTOPS && !defined(Z_PROBE_SLED) + #if defined(SERVO_ENDSTOPS) && !defined(Z_PROBE_SLED) #if SERVO_LEVELING - if (axis == Z_AXIS) engage_z_probe(); else + if (axis == Z_AXIS) deploy_z_probe(); else #endif { if (servo_endstops[axis] > -1) @@ -1486,8 +1485,8 @@ static void homeaxis(int axis) { current_position[axis] = 0; sync_plan_position(); - // Move away from the endstop by the axis HOME_RETRACT_MM - destination[axis] = -home_retract_mm(axis) * axis_home_dir; + // Move away from the endstop by the axis HOME_BUMP_MM + destination[axis] = -home_bump_mm(axis) * axis_home_dir; line_to_destination(); st_synchronize(); @@ -1500,7 +1499,7 @@ static void homeaxis(int axis) { } // Move slowly towards the endstop until triggered - destination[axis] = 2 * home_retract_mm(axis) * axis_home_dir; + destination[axis] = 2 * home_bump_mm(axis) * axis_home_dir; line_to_destination(); st_synchronize(); @@ -1554,14 +1553,12 @@ static void homeaxis(int axis) { #endif #if SERVO_LEVELING && !defined(Z_PROBE_SLED) - if (axis == Z_AXIS) retract_z_probe(); + if (axis == Z_AXIS) stow_z_probe(); #endif } } -void refresh_cmd_timeout(void) { previous_millis_cmd = millis(); } - #ifdef FWRETRACT void retract(bool retracting, bool swapretract = false) { @@ -1701,9 +1698,9 @@ inline void gcode_G4() { if (code_seen('S')) codenum = code_value_long() * 1000; // seconds to wait st_synchronize(); - previous_millis_cmd = millis(); + refresh_cmd_timeout(); codenum += previous_millis_cmd; // keep track of when we started waiting - while(millis() < codenum) { + while (millis() < codenum) { manage_heater(); manage_inactivity(); lcd_update(); @@ -1753,14 +1750,17 @@ inline void gcode_G4() { * Zn Home Z, setting Z to n + home_offset[Z_AXIS] */ inline void gcode_G28() { + + // For auto bed leveling, clear the level matrix #ifdef ENABLE_AUTO_BED_LEVELING - plan_bed_level_matrix.set_to_identity(); //Reset the plane ("erase" all leveling data) + plan_bed_level_matrix.set_to_identity(); #ifdef DELTA reset_bed_level(); #endif #endif - #if defined(MESH_BED_LEVELING) + // For manual bed leveling deactivate the matrix temporarily + #ifdef MESH_BED_LEVELING uint8_t mbl_was_active = mbl.active; mbl.active = 0; #endif @@ -1768,7 +1768,7 @@ inline void gcode_G28() { saved_feedrate = feedrate; saved_feedmultiply = feedmultiply; feedmultiply = 100; - previous_millis_cmd = millis(); + refresh_cmd_timeout(); enable_endstops(true); @@ -1780,10 +1780,11 @@ inline void gcode_G28() { // A delta can only safely home all axis at the same time // all axis have to home at the same time - // Move all carriages up together until the first endstop is hit. + // Pretend the current position is 0,0,0 for (int i = X_AXIS; i <= Z_AXIS; i++) current_position[i] = 0; sync_plan_position(); + // Move all carriages up together until the first endstop is hit. for (int i = X_AXIS; i <= Z_AXIS; i++) destination[i] = 3 * Z_MAX_LENGTH; feedrate = 1.732 * homing_feedrate[X_AXIS]; line_to_destination(); @@ -1994,14 +1995,12 @@ inline void gcode_G28() { enable_endstops(false); #endif - #if defined(MESH_BED_LEVELING) + // For manual leveling move back to 0,0 + #ifdef MESH_BED_LEVELING if (mbl_was_active) { current_position[X_AXIS] = mbl.get_x(0); current_position[Y_AXIS] = mbl.get_y(0); - destination[X_AXIS] = current_position[X_AXIS]; - destination[Y_AXIS] = current_position[Y_AXIS]; - destination[Z_AXIS] = current_position[Z_AXIS]; - destination[E_AXIS] = current_position[E_AXIS]; + for (int i = 0; i < NUM_AXIS; i++) destination[i] = current_position[i]; feedrate = homing_feedrate[X_AXIS]; line_to_destination(); st_synchronize(); @@ -2013,25 +2012,14 @@ inline void gcode_G28() { feedrate = saved_feedrate; feedmultiply = saved_feedmultiply; - previous_millis_cmd = millis(); + refresh_cmd_timeout(); endstops_hit_on_purpose(); // clear endstop hit flags } -#if defined(MESH_BED_LEVELING) || defined(ENABLE_AUTO_BED_LEVELING) - - // Check for known positions in X and Y - inline bool can_run_bed_leveling() { - if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) return true; - LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN); - SERIAL_ECHO_START; - SERIAL_ECHOLNPGM(MSG_POSITION_UNKNOWN); - return false; - } - -#endif // MESH_BED_LEVELING || ENABLE_AUTO_BED_LEVELING - #ifdef MESH_BED_LEVELING + enum MeshLevelingState { MeshReport, MeshStart, MeshNext }; + /** * G29: Mesh-based Z-Probe, probes a grid and produces a * mesh to compensate for variable bed height @@ -2045,81 +2033,82 @@ inline void gcode_G28() { */ inline void gcode_G29() { - // Prevent leveling without first homing in X and Y - if (!can_run_bed_leveling()) return; - static int probe_point = -1; - int state = 0; - if (code_seen('S') || code_seen('s')) { - state = code_value_long(); - if (state < 0 || state > 2) { - SERIAL_PROTOCOLPGM("S out of range (0-2).\n"); - return; - } + MeshLevelingState state = code_seen('S') || code_seen('s') ? (MeshLevelingState)code_value_long() : MeshReport; + if (state < 0 || state > 2) { + SERIAL_PROTOCOLLNPGM("S out of range (0-2)."); + return; } - if (state == 0) { // Dump mesh_bed_leveling - if (mbl.active) { - SERIAL_PROTOCOLPGM("Num X,Y: "); - SERIAL_PROTOCOL(MESH_NUM_X_POINTS); - SERIAL_PROTOCOLPGM(","); - SERIAL_PROTOCOL(MESH_NUM_Y_POINTS); - SERIAL_PROTOCOLPGM("\nZ search height: "); - SERIAL_PROTOCOL(MESH_HOME_SEARCH_Z); - SERIAL_PROTOCOLPGM("\nMeasured points:\n"); - for (int y=0; y 4) { - SERIAL_PROTOCOLPGM("?(V)erbose Level is implausible (0-4).\n"); - return; - } + int verbose_level = code_seen('V') || code_seen('v') ? code_value_long() : 1; + if (verbose_level < 0 || verbose_level > 4) { + SERIAL_ECHOLNPGM("?(V)erbose Level is implausible (0-4)."); + return; } - bool dryrun = code_seen('D') || code_seen('d'); - bool engage_probe_for_each_reading = code_seen('E') || code_seen('e'); + bool dryrun = code_seen('D') || code_seen('d'), + engage_probe_for_each_reading = code_seen('E') || code_seen('e'); #ifdef AUTO_BED_LEVELING_GRID @@ -2188,7 +2178,7 @@ inline void gcode_G28() { if (verbose_level > 0) { SERIAL_PROTOCOLPGM("G29 Auto Bed Leveling\n"); - if (dryrun) SERIAL_ECHOLN("Running in DRY-RUN mode"); + if (dryrun) SERIAL_ECHOLNPGM("Running in DRY-RUN mode"); } int auto_bed_leveling_grid_points = AUTO_BED_LEVELING_GRID_POINTS; @@ -2241,7 +2231,7 @@ inline void gcode_G28() { #ifdef Z_PROBE_SLED dock_sled(false); // engage (un-dock) the probe #elif defined(Z_PROBE_ALLEN_KEY) //|| defined(SERVO_LEVELING) - engage_z_probe(); + deploy_z_probe(); #endif st_synchronize(); @@ -2464,7 +2454,7 @@ inline void gcode_G28() { #ifdef Z_PROBE_SLED dock_sled(true, -SLED_DOCKING_OFFSET); // dock the probe, correcting for over-travel #elif defined(Z_PROBE_ALLEN_KEY) //|| defined(SERVO_LEVELING) - retract_z_probe(); + stow_z_probe(); #endif #ifdef Z_PROBE_END_SCRIPT @@ -2476,7 +2466,7 @@ inline void gcode_G28() { #ifndef Z_PROBE_SLED inline void gcode_G30() { - engage_z_probe(); // Engage Z Servo endstop if available + deploy_z_probe(); // Engage Z Servo endstop if available st_synchronize(); // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly setup_for_endstop_move(); @@ -2494,7 +2484,7 @@ inline void gcode_G28() { SERIAL_EOL; clean_up_after_endstop_move(); - retract_z_probe(); // Retract Z Servo endstop if available + stow_z_probe(); // Retract Z Servo endstop if available } #endif //!Z_PROBE_SLED @@ -2554,7 +2544,7 @@ inline void gcode_G92() { lcd_ignore_click(); st_synchronize(); - previous_millis_cmd = millis(); + refresh_cmd_timeout(); if (codenum > 0) { codenum += previous_millis_cmd; // keep track of when we started waiting while(millis() < codenum && !lcd_clicked()) { @@ -2781,7 +2771,7 @@ inline void gcode_M42() { } } - #if defined(FAN_PIN) && FAN_PIN > -1 + #if HAS_FAN if (pin_number == FAN_PIN) fanSpeed = pin_status; #endif @@ -2915,7 +2905,7 @@ inline void gcode_M42() { // Then retrace the right amount and use that in subsequent probes // - engage_z_probe(); + deploy_z_probe(); setup_for_endstop_move(); run_z_probe(); @@ -2930,7 +2920,7 @@ inline void gcode_M42() { st_synchronize(); current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS); - if (engage_probe_for_each_reading) retract_z_probe(); + if (engage_probe_for_each_reading) stow_z_probe(); for (uint16_t n=0; n < n_samples; n++) { @@ -2973,7 +2963,7 @@ inline void gcode_M42() { } // n_legs if (engage_probe_for_each_reading) { - engage_z_probe(); + deploy_z_probe(); delay(1000); } @@ -3020,13 +3010,13 @@ inline void gcode_M42() { st_synchronize(); if (engage_probe_for_each_reading) { - retract_z_probe(); + stow_z_probe(); delay(1000); } } if (!engage_probe_for_each_reading) { - retract_z_probe(); + stow_z_probe(); delay(1000); } @@ -3067,17 +3057,17 @@ inline void gcode_M104() { inline void gcode_M105() { if (setTargetedHotend(105)) return; - #if defined(TEMP_0_PIN) && TEMP_0_PIN > -1 + #if HAS_TEMP_0 SERIAL_PROTOCOLPGM("ok T:"); SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1); SERIAL_PROTOCOLPGM(" /"); SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1); - #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1 + #if HAS_TEMP_BED SERIAL_PROTOCOLPGM(" B:"); SERIAL_PROTOCOL_F(degBed(),1); SERIAL_PROTOCOLPGM(" /"); SERIAL_PROTOCOL_F(degTargetBed(),1); - #endif //TEMP_BED_PIN + #endif // HAS_TEMP_BED for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) { SERIAL_PROTOCOLPGM(" T"); SERIAL_PROTOCOL(cur_extruder); @@ -3086,7 +3076,7 @@ inline void gcode_M105() { SERIAL_PROTOCOLPGM(" /"); SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1); } - #else + #else // !HAS_TEMP_0 SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_NO_THERMISTORS); #endif @@ -3108,7 +3098,7 @@ inline void gcode_M105() { #endif #ifdef SHOW_TEMP_ADC_VALUES - #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1 + #if HAS_TEMP_BED SERIAL_PROTOCOLPGM(" ADC B:"); SERIAL_PROTOCOL_F(degBed(),1); SERIAL_PROTOCOLPGM("C->"); @@ -3127,7 +3117,7 @@ inline void gcode_M105() { SERIAL_PROTOCOLLN(""); } -#if defined(FAN_PIN) && FAN_PIN > -1 +#if HAS_FAN /** * M106: Set Fan Speed @@ -3220,10 +3210,11 @@ inline void gcode_M109() { } LCD_MESSAGEPGM(MSG_HEATING_COMPLETE); - starttime = previous_millis_cmd = millis(); + refresh_cmd_timeout(); + starttime = previous_millis_cmd; } -#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1 +#if HAS_TEMP_BED /** * M190: Sxxx Wait for bed current temp to reach target temp. Waits only when heating @@ -3258,10 +3249,10 @@ inline void gcode_M109() { lcd_update(); } LCD_MESSAGEPGM(MSG_BED_DONE); - previous_millis_cmd = millis(); + refresh_cmd_timeout(); } -#endif // TEMP_BED_PIN > -1 +#endif // HAS_TEMP_BED /** * M112: Emergency Stop @@ -3272,7 +3263,7 @@ inline void gcode_M112() { #ifdef BARICUDA - #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1 + #if HAS_HEATER_1 /** * M126: Heater 1 valve open */ @@ -3283,7 +3274,7 @@ inline void gcode_M112() { inline void gcode_M127() { ValvePressure = 0; } #endif - #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1 + #if HAS_HEATER_2 /** * M128: Heater 2 valve open */ @@ -3314,7 +3305,7 @@ inline void gcode_M140() { // If you have a switch on suicide pin, this is useful // if you want to start another print with suicide feature after // a print without suicide... - #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1 + #if HAS_SUICIDE OUT_WRITE(SUICIDE_PIN, HIGH); #endif @@ -3342,7 +3333,7 @@ inline void gcode_M81() { finishAndDisableSteppers(); fanSpeed = 0; delay(1000); // Wait 1 second before switching off - #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1 + #if HAS_SUICIDE st_synchronize(); suicide(); #elif HAS_POWER_SWITCH @@ -3498,31 +3489,31 @@ inline void gcode_M117() { */ inline void gcode_M119() { SERIAL_PROTOCOLLN(MSG_M119_REPORT); - #if defined(X_MIN_PIN) && X_MIN_PIN > -1 + #if HAS_X_MIN SERIAL_PROTOCOLPGM(MSG_X_MIN); SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif - #if defined(X_MAX_PIN) && X_MAX_PIN > -1 + #if HAS_X_MAX SERIAL_PROTOCOLPGM(MSG_X_MAX); SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif - #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1 + #if HAS_Y_MIN SERIAL_PROTOCOLPGM(MSG_Y_MIN); SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif - #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1 + #if HAS_Y_MAX SERIAL_PROTOCOLPGM(MSG_Y_MAX); SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif - #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1 + #if HAS_Z_MIN SERIAL_PROTOCOLPGM(MSG_Z_MIN); SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif - #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1 + #if HAS_Z_MAX SERIAL_PROTOCOLPGM(MSG_Z_MAX); SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif - #if defined(Z2_MAX_PIN) && Z2_MAX_PIN > -1 + #if HAS_Z2_MAX SERIAL_PROTOCOLPGM(MSG_Z2_MAX); SERIAL_PROTOCOLLN(((READ(Z2_MAX_PIN)^Z2_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif @@ -4013,7 +4004,7 @@ inline void gcode_M226() { #endif // PIDTEMPBED -#if defined(CHDK) || (defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1) +#if defined(CHDK) || HAS_PHOTOGRAPH /** * M240: Trigger a camera by emulating a Canon RC-1 @@ -4026,7 +4017,7 @@ inline void gcode_M226() { chdkHigh = millis(); chdkActive = true; - #elif defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1 + #elif HAS_PHOTOGRAPH const uint8_t NUM_PULSES = 16; const float PULSE_LENGTH = 0.01524; @@ -4044,7 +4035,7 @@ inline void gcode_M226() { _delay_ms(PULSE_LENGTH); } - #endif // !CHDK && PHOTOGRAPH_PIN > -1 + #endif // !CHDK && HAS_PHOTOGRAPH } #endif // CHDK || PHOTOGRAPH_PIN @@ -4165,17 +4156,17 @@ inline void gcode_M303() { case 0: OUT_WRITE(SOL0_PIN, HIGH); break; - #if defined(SOL1_PIN) && SOL1_PIN > -1 + #if HAS_SOLENOID_1 case 1: OUT_WRITE(SOL1_PIN, HIGH); break; #endif - #if defined(SOL2_PIN) && SOL2_PIN > -1 + #if HAS_SOLENOID_2 case 2: OUT_WRITE(SOL2_PIN, HIGH); break; #endif - #if defined(SOL3_PIN) && SOL3_PIN > -1 + #if HAS_SOLENOID_3 case 3: OUT_WRITE(SOL3_PIN, HIGH); break; @@ -4218,11 +4209,11 @@ inline void gcode_M400() { st_synchronize(); } /** * M401: Engage Z Servo endstop if available */ - inline void gcode_M401() { engage_z_probe(); } + inline void gcode_M401() { deploy_z_probe(); } /** * M402: Retract Z Servo endstop if enabled */ - inline void gcode_M402() { retract_z_probe(); } + inline void gcode_M402() { stow_z_probe(); } #endif @@ -4232,7 +4223,7 @@ inline void gcode_M400() { st_synchronize(); } * M404: Display or set the nominal filament width (3mm, 1.75mm ) W<3.0> */ inline void gcode_M404() { - #if FILWIDTH_PIN > -1 + #if HAS_FILWIDTH if (code_seen('W')) { filament_width_nominal = code_value(); } @@ -4555,22 +4546,21 @@ inline void gcode_M907() { #endif // HAS_DIGIPOTSS -// M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. -inline void gcode_M350() { - #if defined(X_MS1_PIN) && X_MS1_PIN > -1 +#if HAS_MICROSTEPS + + // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. + inline void gcode_M350() { if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value()); for(int i=0;i -1 + /** + * M351: Toggle MS1 MS2 pins directly with axis codes X Y Z E B + * S# determines MS1 or MS2, X# sets the pin high/low. + */ + inline void gcode_M351() { if (code_seen('S')) switch(code_value_long()) { case 1: for(int i=0;i -1 + #if HAS_TEMP_BED case 190: // M190 - Wait for bed heater to reach target. gcode_M190(); break; - #endif //TEMP_BED_PIN + #endif // HAS_TEMP_BED - #if defined(FAN_PIN) && FAN_PIN > -1 + #if HAS_FAN case 106: //M106 Fan On gcode_M106(); break; case 107: //M107 Fan Off gcode_M107(); break; - #endif //FAN_PIN + #endif // HAS_FAN #ifdef BARICUDA // PWM for HEATER_1_PIN - #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1 + #if HAS_HEATER_1 case 126: // M126 valve open gcode_M126(); break; case 127: // M127 valve closed gcode_M127(); break; - #endif //HEATER_1_PIN + #endif // HAS_HEATER_1 // PWM for HEATER_2_PIN - #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1 + #if HAS_HEATER_2 case 128: // M128 valve open gcode_M128(); break; case 129: // M129 valve closed gcode_M129(); break; - #endif //HEATER_2_PIN - #endif //BARICUDA + #endif // HAS_HEATER_2 + #endif // BARICUDA #if HAS_POWER_SWITCH @@ -5035,7 +5027,7 @@ void process_commands() { break; #endif // PIDTEMPBED - #if defined(CHDK) || (defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1) + #if defined(CHDK) || HAS_PHOTOGRAPH case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/ gcode_M240(); break; @@ -5153,13 +5145,17 @@ void process_commands() { break; #endif // HAS_DIGIPOTSS - case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. - gcode_M350(); - break; + #if HAS_MICROSTEPS - case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. - gcode_M351(); - break; + case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. + gcode_M350(); + break; + + case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. + gcode_M351(); + break; + + #endif // HAS_MICROSTEPS case 999: // M999: Restart after being Stopped gcode_M999(); @@ -5181,8 +5177,7 @@ void process_commands() { ClearToSend(); } -void FlushSerialRequestResend() -{ +void FlushSerialRequestResend() { //char cmdbuffer[bufindr][100]="Resend:"; MYSERIAL.flush(); SERIAL_PROTOCOLPGM(MSG_RESEND); @@ -5190,13 +5185,11 @@ void FlushSerialRequestResend() ClearToSend(); } -void ClearToSend() -{ - previous_millis_cmd = millis(); +void ClearToSend() { + refresh_cmd_timeout(); #ifdef SDSUPPORT - if(fromsd[bufindr]) - return; - #endif //SDSUPPORT + if (fromsd[bufindr]) return; + #endif SERIAL_PROTOCOLLNPGM(MSG_OK); } @@ -5213,29 +5206,18 @@ void get_coordinates() { } } -void get_arc_coordinates() -{ -#ifdef SF_ARC_FIX - bool relative_mode_backup = relative_mode; - relative_mode = true; -#endif - get_coordinates(); -#ifdef SF_ARC_FIX - relative_mode=relative_mode_backup; -#endif +void get_arc_coordinates() { + #ifdef SF_ARC_FIX + bool relative_mode_backup = relative_mode; + relative_mode = true; + #endif + get_coordinates(); + #ifdef SF_ARC_FIX + relative_mode = relative_mode_backup; + #endif - if(code_seen('I')) { - offset[0] = code_value(); - } - else { - offset[0] = 0.0; - } - if(code_seen('J')) { - offset[1] = code_value(); - } - else { - offset[1] = 0.0; - } + offset[0] = code_seen('I') ? code_value() : 0; + offset[1] = code_seen('J') ? code_value() : 0; } void clamp_to_software_endstops(float target[3]) @@ -5299,7 +5281,6 @@ void clamp_to_software_endstops(float target[3]) #ifdef ENABLE_AUTO_BED_LEVELING // Adjust print surface height by linear interpolation over the bed_level array. - int delta_grid_spacing[2] = { 0, 0 }; void adjust_delta(float cartesian[3]) { if (delta_grid_spacing[0] == 0 || delta_grid_spacing[1] == 0) return; // G29 not done! @@ -5339,16 +5320,9 @@ void clamp_to_software_endstops(float target[3]) } #endif // ENABLE_AUTO_BED_LEVELING - void prepare_move_raw() { - previous_millis_cmd = millis(); - calculate_delta(destination); - plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], (feedrate/60)*(feedmultiply/100.0), active_extruder); - for (int i = 0; i < NUM_AXIS; i++) current_position[i] = destination[i]; - } - #endif // DELTA -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #if !defined(MIN) #define MIN(_v1, _v2) (((_v1) < (_v2)) ? (_v1) : (_v2)) @@ -5427,7 +5401,7 @@ void mesh_plan_buffer_line(float x, float y, float z, const float e, float feed_ void prepare_move() { clamp_to_software_endstops(destination); - previous_millis_cmd = millis(); + refresh_cmd_timeout(); #ifdef SCARA //for now same as delta-code @@ -5544,7 +5518,7 @@ void prepare_move() { if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) { line_to_destination(); } else { -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING mesh_plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], (feedrate/60)*(feedmultiply/100.0), active_extruder); return; #else @@ -5570,16 +5544,10 @@ void prepare_arc_move(char isclockwise) { for(int8_t i=0; i < NUM_AXIS; i++) { current_position[i] = destination[i]; } - previous_millis_cmd = millis(); + refresh_cmd_timeout(); } -#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1 - -#if defined(FAN_PIN) - #if CONTROLLERFAN_PIN == FAN_PIN - #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN" - #endif -#endif +#if HAS_CONTROLLERFAN unsigned long lastMotor = 0; // Last time a motor was turned on unsigned long lastMotorCheck = 0; // Last time the state was checked @@ -5592,7 +5560,7 @@ void controllerFan() { || E0_ENABLE_READ == E_ENABLE_ON // If any of the drivers are enabled... #if EXTRUDERS > 1 || E1_ENABLE_READ == E_ENABLE_ON - #if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1 + #if HAS_X2_ENABLE || X2_ENABLE_READ == X_ENABLE_ON #endif #if EXTRUDERS > 2 @@ -5704,7 +5672,7 @@ void handle_status_leds(void) { max_temp = max(max_temp, degHotend(cur_extruder)); max_temp = max(max_temp, degTargetHotend(cur_extruder)); } - #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1 + #if HAS_TEMP_BED max_temp = max(max_temp, degTargetBed()); max_temp = max(max_temp, degBed()); #endif @@ -5724,134 +5692,120 @@ void handle_status_leds(void) { } #endif -void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h -{ +void disable_all_axes() { + disable_x(); + disable_y(); + disable_z(); + disable_e0(); + disable_e1(); + disable_e2(); + disable_e3(); +} + +/** + * + */ +void manage_inactivity(bool ignore_stepper_queue/*=false*/) { -#if defined(KILL_PIN) && KILL_PIN > -1 - static int killCount = 0; // make the inactivity button a bit less responsive - const int KILL_DELAY = 750; -#endif + #if HAS_KILL + static int killCount = 0; // make the inactivity button a bit less responsive + const int KILL_DELAY = 750; + #endif -#if defined(FILRUNOUT_PIN) && FILRUNOUT_PIN > -1 - if(card.sdprinting) { - if(!(READ(FILRUNOUT_PIN))^FIL_RUNOUT_INVERTING) - filrunout(); } -#endif + #if HAS_FILRUNOUT + if (card.sdprinting && !(READ(FILRUNOUT_PIN) ^ FIL_RUNOUT_INVERTING)) + filrunout(); + #endif + + #if HAS_HOME + static int homeDebounceCount = 0; // poor man's debouncing count + const int HOME_DEBOUNCE_DELAY = 750; + #endif + + if (buflen < BUFSIZE - 1) get_command(); + + unsigned long ms = millis(); + + if (max_inactive_time && ms > previous_millis_cmd + max_inactive_time) kill(); + + if (stepper_inactive_time && ms > previous_millis_cmd + stepper_inactive_time + && !ignore_stepper_queue && !blocks_queued()) + disable_all_axes(); -#if defined(HOME_PIN) && HOME_PIN > -1 - static int homeDebounceCount = 0; // poor man's debouncing count - const int HOME_DEBOUNCE_DELAY = 750; -#endif - - - if(buflen < (BUFSIZE-1)) - get_command(); - - if( (millis() - previous_millis_cmd) > max_inactive_time ) - if(max_inactive_time) - kill(); - if(stepper_inactive_time) { - if( (millis() - previous_millis_cmd) > stepper_inactive_time ) - { - if(blocks_queued() == false && ignore_stepper_queue == false) { - disable_x(); - disable_y(); - disable_z(); - disable_e0(); - disable_e1(); - disable_e2(); - disable_e3(); - } - } - } - #ifdef CHDK //Check if pin should be set to LOW after M240 set it to HIGH - if (chdkActive && (millis() - chdkHigh > CHDK_DELAY)) - { + if (chdkActive && ms > chdkHigh + CHDK_DELAY) { chdkActive = false; WRITE(CHDK, LOW); } #endif - - #if defined(KILL_PIN) && KILL_PIN > -1 + + #if HAS_KILL // Check if the kill button was pressed and wait just in case it was an accidental // key kill key press // ------------------------------------------------------------------------------- - if( 0 == READ(KILL_PIN) ) - { + if (!READ(KILL_PIN)) killCount++; - } else if (killCount > 0) - { killCount--; - } + // Exceeded threshold and we can confirm that it was not accidental // KILL the machine // ---------------------------------------------------------------- - if ( killCount >= KILL_DELAY) - { - kill(); - } + if (killCount >= KILL_DELAY) kill(); #endif -#if defined(HOME_PIN) && HOME_PIN > -1 + #if HAS_HOME // Check to see if we have to home, use poor man's debouncer // --------------------------------------------------------- - if ( 0 == READ(HOME_PIN) ) - { - if (homeDebounceCount == 0) - { - enquecommands_P((PSTR("G28"))); - homeDebounceCount++; - LCD_ALERTMESSAGEPGM(MSG_AUTO_HOME); - } - else if (homeDebounceCount < HOME_DEBOUNCE_DELAY) - { - homeDebounceCount++; - } - else - { - homeDebounceCount = 0; - } + if (!READ(HOME_PIN)) { + if (!homeDebounceCount) { + enquecommands_P(PSTR("G28")); + LCD_ALERTMESSAGEPGM(MSG_AUTO_HOME); + } + if (homeDebounceCount < HOME_DEBOUNCE_DELAY) + homeDebounceCount++; + else + homeDebounceCount = 0; } -#endif + #endif - #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1 + #if HAS_CONTROLLERFAN controllerFan(); //Check if fan should be turned on to cool stepper drivers down #endif + #ifdef EXTRUDER_RUNOUT_PREVENT - if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 ) - if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP) - { - bool oldstatus=E0_ENABLE_READ; - enable_e0(); - float oldepos=current_position[E_AXIS]; - float oldedes=destination[E_AXIS]; - plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], - destination[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], - EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], active_extruder); - current_position[E_AXIS]=oldepos; - destination[E_AXIS]=oldedes; - plan_set_e_position(oldepos); - previous_millis_cmd=millis(); - st_synchronize(); - E0_ENABLE_WRITE(oldstatus); + if (ms > previous_millis_cmd + EXTRUDER_RUNOUT_SECONDS * 1000) + if (degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP) { + bool oldstatus = E0_ENABLE_READ; + enable_e0(); + float oldepos = current_position[E_AXIS], oldedes = destination[E_AXIS]; + plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], + destination[E_AXIS] + EXTRUDER_RUNOUT_EXTRUDE * EXTRUDER_RUNOUT_ESTEPS / axis_steps_per_unit[E_AXIS], + EXTRUDER_RUNOUT_SPEED / 60. * EXTRUDER_RUNOUT_ESTEPS / axis_steps_per_unit[E_AXIS], active_extruder); + current_position[E_AXIS] = oldepos; + destination[E_AXIS] = oldedes; + plan_set_e_position(oldepos); + previous_millis_cmd = ms; // refresh_cmd_timeout() + st_synchronize(); + E0_ENABLE_WRITE(oldstatus); } #endif - #if defined(DUAL_X_CARRIAGE) + + #ifdef DUAL_X_CARRIAGE // handle delayed move timeout - if (delayed_move_time != 0 && (millis() - delayed_move_time) > 1000 && Stopped == false) - { + if (delayed_move_time && ms > delayed_move_time + 1000 && !Stopped) { // travel moves have been received so enact them delayed_move_time = 0xFFFFFFFFUL; // force moves to be done - memcpy(destination,current_position,sizeof(destination)); + memcpy(destination,current_position, sizeof(destination)); prepare_move(); } #endif + #ifdef TEMP_STAT_LEDS - handle_status_leds(); + handle_status_leds(); #endif + check_axes_activity(); } diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 8c05f83bc..e072c7d73 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -56,7 +56,7 @@ #if EXTRUDERS > 1 #if EXTRUDERS > 4 - #error The maximum number of EXTRUDERS is 4. + #error The maximum number of EXTRUDERS in Marlin is 4. #endif #ifdef TEMP_SENSOR_1_AS_REDUNDANT @@ -77,6 +77,13 @@ #endif // EXTRUDERS > 1 + /** + * Limited number of servos + */ + #if NUM_SERVOS > 4 + #error The maximum number of SERVOS in Marlin is 4. + #endif + /** * Required LCD language */ @@ -209,9 +216,9 @@ */ #ifdef DUAL_X_CARRIAGE #if EXTRUDERS == 1 || defined(COREXY) \ - || !defined(X2_ENABLE_PIN) || !defined(X2_STEP_PIN) || !defined(X2_DIR_PIN) \ + || !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR \ || !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \ - || !defined(X_MAX_PIN) || X_MAX_PIN < 0 + || !HAS_X_MAX #error Missing or invalid definitions for DUAL_X_CARRIAGE mode. #endif #if X_HOME_DIR != -1 || X2_HOME_DIR != 1 @@ -234,6 +241,10 @@ #endif #endif + #if HAS_FAN && CONTROLLERFAN_PIN == FAN_PIN + #error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN + #endif + /** * Test required HEATER defines */ @@ -254,4 +265,11 @@ #error HEATER_0_PIN not defined for this board #endif + /** + * Warnings for old configurations + */ + #ifdef X_HOME_RETRACT_MM + #error [XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM + #endif + #endif //SANITYCHECK_H diff --git a/Marlin/configurator/config/Configuration.h b/Marlin/configurator/config/Configuration.h index 7868e8e81..3e1a56dc4 100644 --- a/Marlin/configurator/config/Configuration.h +++ b/Marlin/configurator/config/Configuration.h @@ -412,7 +412,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/configurator/config/Configuration_adv.h b/Marlin/configurator/config/Configuration_adv.h index 21b30580c..8acdeb969 100644 --- a/Marlin/configurator/config/Configuration_adv.h +++ b/Marlin/configurator/config/Configuration_adv.h @@ -189,9 +189,9 @@ // @section homing //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 2 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 2 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/dogm_lcd_implementation.h b/Marlin/dogm_lcd_implementation.h index 63e99bd3a..c057e5642 100644 --- a/Marlin/dogm_lcd_implementation.h +++ b/Marlin/dogm_lcd_implementation.h @@ -300,7 +300,7 @@ static void lcd_implementation_status_screen() { // Fan lcd_setFont(FONT_STATUSMENU); u8g.setPrintPos(104,27); - #if defined(FAN_PIN) && FAN_PIN > -1 + #if HAS_FAN int per = ((fanSpeed + 1) * 100) / 256; if (per) { diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 1cc50246a..4c8353823 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -364,7 +364,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/Felix/Configuration_DUAL.h b/Marlin/example_configurations/Felix/Configuration_DUAL.h index 956e2dc47..a0ecacd92 100644 --- a/Marlin/example_configurations/Felix/Configuration_DUAL.h +++ b/Marlin/example_configurations/Felix/Configuration_DUAL.h @@ -364,7 +364,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 9bbd515ca..d60eb5296 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 3 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 3 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 594295a3e..e66222346 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -387,7 +387,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index bac3b571a..0529df9be 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 2 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 2 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index c17e419c7..854367af8 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -392,7 +392,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 9bbd515ca..d60eb5296 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 3 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 3 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 96fef00cf..15fde93f8 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -416,7 +416,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 7b00532e4..5145b1668 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 3 -#define Y_HOME_RETRACT_MM 3 -#define Z_HOME_RETRACT_MM 3 +#define X_HOME_BUMP_MM 3 +#define Y_HOME_BUMP_MM 3 +#define Z_HOME_BUMP_MM 3 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 190270e85..5bccb9827 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -386,7 +386,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 965ecbf40..ab480dd63 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 2 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 2 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 4aeb5d55f..1403ddd2d 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -414,7 +414,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 @@ -507,10 +507,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #define Z_PROBE_ALLEN_KEY_DEPLOY_Y DELTA_PRINTABLE_RADIUS #define Z_PROBE_ALLEN_KEY_DEPLOY_Z 100 - #define Z_PROBE_ALLEN_KEY_RETRACT_X -64 - #define Z_PROBE_ALLEN_KEY_RETRACT_Y 56 - #define Z_PROBE_ALLEN_KEY_RETRACT_Z 23 - #define Z_PROBE_ALLEN_KEY_RETRACT_DEPTH 20 + #define Z_PROBE_ALLEN_KEY_STOW_X -64 + #define Z_PROBE_ALLEN_KEY_STOW_Y 56 + #define Z_PROBE_ALLEN_KEY_STOW_Z 23 + #define Z_PROBE_ALLEN_KEY_STOW_DEPTH 20 #endif //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index abecacec2..501cd814d 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 5 // deltas need the same for all three axis +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index edb7ff526..420dfa9e4 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -414,7 +414,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 @@ -511,10 +511,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o #define Z_PROBE_ALLEN_KEY_DEPLOY_Y DELTA_PRINTABLE_RADIUS #define Z_PROBE_ALLEN_KEY_DEPLOY_Z 100 - #define Z_PROBE_ALLEN_KEY_RETRACT_X -64 - #define Z_PROBE_ALLEN_KEY_RETRACT_Y 56 - #define Z_PROBE_ALLEN_KEY_RETRACT_Z 23 - #define Z_PROBE_ALLEN_KEY_RETRACT_DEPTH 20 + #define Z_PROBE_ALLEN_KEY_STOW_X -64 + #define Z_PROBE_ALLEN_KEY_STOW_Y 56 + #define Z_PROBE_ALLEN_KEY_STOW_Z 23 + #define Z_PROBE_ALLEN_KEY_STOW_DEPTH 20 #endif //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index b255000bc..c402064bf 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 5 // deltas need the same for all three axis +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index a3e8fd088..55e26ebf8 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -384,7 +384,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 5e0e6ef4d..3db90efcf 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 2 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 2 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 7ffff3353..6b781b7a4 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -386,7 +386,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of // #define MANUAL_BED_LEVELING // Add display menu option for bed leveling // #define MESH_BED_LEVELING // Enable mesh bed leveling -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_MIN_X 10 #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X) #define MESH_MIN_Y 10 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index bbf7dc005..2ecf75951 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -175,9 +175,9 @@ #endif //DUAL_X_CARRIAGE //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: -#define X_HOME_RETRACT_MM 5 -#define Y_HOME_RETRACT_MM 5 -#define Z_HOME_RETRACT_MM 1 +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 1 #define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. diff --git a/Marlin/mesh_bed_leveling.h b/Marlin/mesh_bed_leveling.h index b6c4ed5b0..bf7275e5c 100644 --- a/Marlin/mesh_bed_leveling.h +++ b/Marlin/mesh_bed_leveling.h @@ -1,6 +1,6 @@ #include "Marlin.h" -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #define MESH_X_DIST ((MESH_MAX_X - MESH_MIN_X)/(MESH_NUM_X_POINTS - 1)) #define MESH_Y_DIST ((MESH_MAX_Y - MESH_MIN_Y)/(MESH_NUM_Y_POINTS - 1)) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index d98ef63d4..d7d33c170 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -58,7 +58,7 @@ #include "ultralcd.h" #include "language.h" -#if defined(MESH_BED_LEVELING) +#ifdef MESH_BED_LEVELING #include "mesh_bed_leveling.h" #endif // MESH_BED_LEVELING @@ -427,7 +427,7 @@ void check_axes_activity() { disable_e3(); } - #if defined(FAN_PIN) && FAN_PIN > -1 // HAS_FAN + #if HAS_FAN #ifdef FAN_KICKSTART_TIME static unsigned long fan_kick_end; if (tail_fan_speed) { @@ -447,17 +447,17 @@ void check_axes_activity() { #else analogWrite(FAN_PIN, tail_fan_speed); #endif //!FAN_SOFT_PWM - #endif //FAN_PIN > -1 + #endif // HAS_FAN #ifdef AUTOTEMP getHighESpeed(); #endif #ifdef BARICUDA - #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1 // HAS_HEATER_1 + #if HAS_HEATER_1 analogWrite(HEATER_1_PIN,tail_valve_pressure); #endif - #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1 // HAS_HEATER_2 + #if HAS_HEATER_2 analogWrite(HEATER_2_PIN,tail_e_to_p_pressure); #endif #endif diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index a7dba4659..a9a428c0e 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -85,29 +85,29 @@ static volatile bool endstop_z_hit = false; int motor_current_setting[3] = DEFAULT_PWM_MOTOR_CURRENT; #endif -#if defined(X_MIN_PIN) && X_MIN_PIN >= 0 +#if HAS_X_MIN static bool old_x_min_endstop = false; #endif -#if defined(X_MAX_PIN) && X_MAX_PIN >= 0 +#if HAS_X_MAX static bool old_x_max_endstop = false; #endif -#if defined(Y_MIN_PIN) && Y_MIN_PIN >= 0 +#if HAS_Y_MIN static bool old_y_min_endstop = false; #endif -#if defined(Y_MAX_PIN) && Y_MAX_PIN >= 0 +#if HAS_Y_MAX static bool old_y_max_endstop = false; #endif -#if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0 +#if HAS_Z_MIN static bool old_z_min_endstop = false; #endif -#if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0 +#if HAS_Z_MAX static bool old_z_max_endstop = false; #endif #ifdef Z_DUAL_ENDSTOPS - #if defined(Z2_MIN_PIN) && Z2_MIN_PIN >= 0 + #if HAS_Z2_MIN static bool old_z2_min_endstop = false; #endif - #if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0 + #if HAS_Z2_MAX static bool old_z2_max_endstop = false; #endif #endif @@ -472,7 +472,7 @@ ISR(TIMER1_COMPA_vect) { if ((current_block->active_extruder == 0 && X_HOME_DIR == -1) || (current_block->active_extruder != 0 && X2_HOME_DIR == -1)) #endif { - #if defined(X_MIN_PIN) && X_MIN_PIN >= 0 + #if HAS_X_MIN UPDATE_ENDSTOP(x, X, min, MIN); #endif } @@ -483,7 +483,7 @@ ISR(TIMER1_COMPA_vect) { if ((current_block->active_extruder == 0 && X_HOME_DIR == 1) || (current_block->active_extruder != 0 && X2_HOME_DIR == 1)) #endif { - #if defined(X_MAX_PIN) && X_MAX_PIN >= 0 + #if HAS_X_MAX UPDATE_ENDSTOP(x, X, max, MAX); #endif } @@ -498,12 +498,12 @@ ISR(TIMER1_COMPA_vect) { if (TEST(out_bits, Y_AXIS)) // -direction #endif { // -direction - #if defined(Y_MIN_PIN) && Y_MIN_PIN >= 0 + #if HAS_Y_MIN UPDATE_ENDSTOP(y, Y, min, MIN); #endif } else { // +direction - #if defined(Y_MAX_PIN) && Y_MAX_PIN >= 0 + #if HAS_Y_MAX UPDATE_ENDSTOP(y, Y, max, MAX); #endif } @@ -519,13 +519,13 @@ ISR(TIMER1_COMPA_vect) { if (check_endstops) { - #if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0 + #if HAS_Z_MIN #ifdef Z_DUAL_ENDSTOPS bool z_min_endstop = READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING, z2_min_endstop = - #if defined(Z2_MIN_PIN) && Z2_MIN_PIN >= 0 + #if HAS_Z2_MIN READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING #else z_min_endstop @@ -561,13 +561,13 @@ ISR(TIMER1_COMPA_vect) { if (check_endstops) { - #if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0 + #if HAS_Z_MAX #ifdef Z_DUAL_ENDSTOPS bool z_max_endstop = READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING, z2_max_endstop = - #if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0 + #if HAS_Z2_MAX READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING #else z_max_endstop @@ -835,127 +835,127 @@ void st_init() { #endif // Initialize Dir Pins - #if defined(X_DIR_PIN) && X_DIR_PIN >= 0 + #if HAS_X_DIR X_DIR_INIT; #endif - #if defined(X2_DIR_PIN) && X2_DIR_PIN >= 0 + #if HAS_X2_DIR X2_DIR_INIT; #endif - #if defined(Y_DIR_PIN) && Y_DIR_PIN >= 0 + #if HAS_Y_DIR Y_DIR_INIT; - #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_DIR_PIN) && Y2_DIR_PIN >= 0 + #if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_DIR Y2_DIR_INIT; #endif #endif - #if defined(Z_DIR_PIN) && Z_DIR_PIN >= 0 + #if HAS_Z_DIR Z_DIR_INIT; - #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_DIR_PIN) && Z2_DIR_PIN >= 0 + #if defined(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_DIR Z2_DIR_INIT; #endif #endif - #if defined(E0_DIR_PIN) && E0_DIR_PIN >= 0 + #if HAS_E0_DIR E0_DIR_INIT; #endif - #if defined(E1_DIR_PIN) && E1_DIR_PIN >= 0 + #if HAS_E1_DIR E1_DIR_INIT; #endif - #if defined(E2_DIR_PIN) && E2_DIR_PIN >= 0 + #if HAS_E2_DIR E2_DIR_INIT; #endif - #if defined(E3_DIR_PIN) && E3_DIR_PIN >= 0 + #if HAS_E3_DIR E3_DIR_INIT; #endif //Initialize Enable Pins - steppers default to disabled. - #if defined(X_ENABLE_PIN) && X_ENABLE_PIN >= 0 + #if HAS_X_ENABLE X_ENABLE_INIT; if (!X_ENABLE_ON) X_ENABLE_WRITE(HIGH); #endif - #if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN >= 0 + #if HAS_X2_ENABLE X2_ENABLE_INIT; if (!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH); #endif - #if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN >= 0 + #if HAS_Y_ENABLE Y_ENABLE_INIT; if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH); - #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_ENABLE_PIN) && Y2_ENABLE_PIN >= 0 + #if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_ENABLE Y2_ENABLE_INIT; if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH); #endif #endif - #if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN >= 0 + #if HAS_Z_ENABLE Z_ENABLE_INIT; if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH); - #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_ENABLE_PIN) && Z2_ENABLE_PIN >= 0 + #if defined(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_ENABLE Z2_ENABLE_INIT; if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH); #endif #endif - #if defined(E0_ENABLE_PIN) && E0_ENABLE_PIN >= 0 + #if HAS_E0_ENABLE E0_ENABLE_INIT; if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH); #endif - #if defined(E1_ENABLE_PIN) && E1_ENABLE_PIN >= 0 + #if HAS_E1_ENABLE E1_ENABLE_INIT; if (!E_ENABLE_ON) E1_ENABLE_WRITE(HIGH); #endif - #if defined(E2_ENABLE_PIN) && E2_ENABLE_PIN >= 0 + #if HAS_E2_ENABLE E2_ENABLE_INIT; if (!E_ENABLE_ON) E2_ENABLE_WRITE(HIGH); #endif - #if defined(E3_ENABLE_PIN) && E3_ENABLE_PIN >= 0 + #if HAS_E3_ENABLE E3_ENABLE_INIT; if (!E_ENABLE_ON) E3_ENABLE_WRITE(HIGH); #endif //endstops and pullups - #if defined(X_MIN_PIN) && X_MIN_PIN >= 0 + #if HAS_X_MIN SET_INPUT(X_MIN_PIN); #ifdef ENDSTOPPULLUP_XMIN WRITE(X_MIN_PIN,HIGH); #endif #endif - #if defined(Y_MIN_PIN) && Y_MIN_PIN >= 0 + #if HAS_Y_MIN SET_INPUT(Y_MIN_PIN); #ifdef ENDSTOPPULLUP_YMIN WRITE(Y_MIN_PIN,HIGH); #endif #endif - #if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0 + #if HAS_Z_MIN SET_INPUT(Z_MIN_PIN); #ifdef ENDSTOPPULLUP_ZMIN WRITE(Z_MIN_PIN,HIGH); #endif #endif - #if defined(X_MAX_PIN) && X_MAX_PIN >= 0 + #if HAS_X_MAX SET_INPUT(X_MAX_PIN); #ifdef ENDSTOPPULLUP_XMAX WRITE(X_MAX_PIN,HIGH); #endif #endif - #if defined(Y_MAX_PIN) && Y_MAX_PIN >= 0 + #if HAS_Y_MAX SET_INPUT(Y_MAX_PIN); #ifdef ENDSTOPPULLUP_YMAX WRITE(Y_MAX_PIN,HIGH); #endif #endif - #if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0 + #if HAS_Z_MAX SET_INPUT(Z_MAX_PIN); #ifdef ENDSTOPPULLUP_ZMAX WRITE(Z_MAX_PIN,HIGH); #endif #endif - #if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0 + #if HAS_Z2_MAX SET_INPUT(Z2_MAX_PIN); #ifdef ENDSTOPPULLUP_ZMAX WRITE(Z2_MAX_PIN,HIGH); @@ -970,36 +970,36 @@ void st_init() { #define E_AXIS_INIT(NUM) AXIS_INIT(e## NUM, E## NUM, E) // Initialize Step Pins - #if defined(X_STEP_PIN) && X_STEP_PIN >= 0 + #if HAS_X_STEP AXIS_INIT(x, X, X); #endif - #if defined(X2_STEP_PIN) && X2_STEP_PIN >= 0 + #if HAS_X2_STEP AXIS_INIT(x, X2, X); #endif - #if defined(Y_STEP_PIN) && Y_STEP_PIN >= 0 - #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_STEP_PIN) && Y2_STEP_PIN >= 0 + #if HAS_Y_STEP + #if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_STEP Y2_STEP_INIT; Y2_STEP_WRITE(INVERT_Y_STEP_PIN); #endif AXIS_INIT(y, Y, Y); #endif - #if defined(Z_STEP_PIN) && Z_STEP_PIN >= 0 - #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_STEP_PIN) && Z2_STEP_PIN >= 0 + #if HAS_Z_STEP + #if defined(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_STEP Z2_STEP_INIT; Z2_STEP_WRITE(INVERT_Z_STEP_PIN); #endif AXIS_INIT(z, Z, Z); #endif - #if defined(E0_STEP_PIN) && E0_STEP_PIN >= 0 + #if HAS_E0_STEP E_AXIS_INIT(0); #endif - #if defined(E1_STEP_PIN) && E1_STEP_PIN >= 0 + #if HAS_E1_STEP E_AXIS_INIT(1); #endif - #if defined(E2_STEP_PIN) && E2_STEP_PIN >= 0 + #if HAS_E2_STEP E_AXIS_INIT(2); #endif - #if defined(E3_STEP_PIN) && E3_STEP_PIN >= 0 + #if HAS_E3_STEP E_AXIS_INIT(3); #endif @@ -1220,12 +1220,12 @@ void digipot_current(uint8_t driver, int current) { } void microstep_init() { - #if defined(E1_MS1_PIN) && E1_MS1_PIN >= 0 + #if HAS_MICROSTEPS_E1 pinMode(E1_MS1_PIN,OUTPUT); - pinMode(E1_MS2_PIN,OUTPUT); + pinMode(E1_MS2_PIN,OUTPUT); #endif - #if defined(X_MS1_PIN) && X_MS1_PIN >= 0 + #if HAS_MICROSTEPS pinMode(X_MS1_PIN,OUTPUT); pinMode(X_MS2_PIN,OUTPUT); pinMode(Y_MS1_PIN,OUTPUT); @@ -1246,7 +1246,7 @@ void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) { case 1: digitalWrite(Y_MS1_PIN, ms1); break; case 2: digitalWrite(Z_MS1_PIN, ms1); break; case 3: digitalWrite(E0_MS1_PIN, ms1); break; - #if defined(E1_MS1_PIN) && E1_MS1_PIN >= 0 + #if HAS_MICROSTEPS_E1 case 4: digitalWrite(E1_MS1_PIN, ms1); break; #endif } @@ -1285,7 +1285,7 @@ void microstep_readings() { SERIAL_PROTOCOLPGM("E0: "); SERIAL_PROTOCOL(digitalRead(E0_MS1_PIN)); SERIAL_PROTOCOLLN(digitalRead(E0_MS2_PIN)); - #if defined(E1_MS1_PIN) && E1_MS1_PIN >= 0 + #if HAS_MICROSTEPS_E1 SERIAL_PROTOCOLPGM("E1: "); SERIAL_PROTOCOL(digitalRead(E1_MS1_PIN)); SERIAL_PROTOCOLLN(digitalRead(E1_MS2_PIN)); diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 79146a355..a6ea1b7d1 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -53,7 +53,7 @@ extern float current_temperature_bed; extern float redundant_temperature; #endif -#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1 +#if HAS_CONTROLLERFAN extern unsigned char soft_pwm_bed; #endif diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index a89c26206..fe4f59768 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -64,14 +64,14 @@ #define LCD_CLICKED (buttons&EN_C) #ifdef REPRAPWORLD_KEYPAD - #define EN_REPRAPWORLD_KEYPAD_F3 BIT(BLEN_REPRAPWORLD_KEYPAD_F3) - #define EN_REPRAPWORLD_KEYPAD_F2 BIT(BLEN_REPRAPWORLD_KEYPAD_F2) - #define EN_REPRAPWORLD_KEYPAD_F1 BIT(BLEN_REPRAPWORLD_KEYPAD_F1) - #define EN_REPRAPWORLD_KEYPAD_UP BIT(BLEN_REPRAPWORLD_KEYPAD_UP) - #define EN_REPRAPWORLD_KEYPAD_RIGHT BIT(BLEN_REPRAPWORLD_KEYPAD_RIGHT) - #define EN_REPRAPWORLD_KEYPAD_MIDDLE BIT(BLEN_REPRAPWORLD_KEYPAD_MIDDLE) - #define EN_REPRAPWORLD_KEYPAD_DOWN BIT(BLEN_REPRAPWORLD_KEYPAD_DOWN) - #define EN_REPRAPWORLD_KEYPAD_LEFT BIT(BLEN_REPRAPWORLD_KEYPAD_LEFT) + #define EN_REPRAPWORLD_KEYPAD_F3 (BIT(BLEN_REPRAPWORLD_KEYPAD_F3)) + #define EN_REPRAPWORLD_KEYPAD_F2 (BIT(BLEN_REPRAPWORLD_KEYPAD_F2)) + #define EN_REPRAPWORLD_KEYPAD_F1 (BIT(BLEN_REPRAPWORLD_KEYPAD_F1)) + #define EN_REPRAPWORLD_KEYPAD_UP (BIT(BLEN_REPRAPWORLD_KEYPAD_UP)) + #define EN_REPRAPWORLD_KEYPAD_RIGHT (BIT(BLEN_REPRAPWORLD_KEYPAD_RIGHT)) + #define EN_REPRAPWORLD_KEYPAD_MIDDLE (BIT(BLEN_REPRAPWORLD_KEYPAD_MIDDLE)) + #define EN_REPRAPWORLD_KEYPAD_DOWN (BIT(BLEN_REPRAPWORLD_KEYPAD_DOWN)) + #define EN_REPRAPWORLD_KEYPAD_LEFT (BIT(BLEN_REPRAPWORLD_KEYPAD_LEFT)) #define LCD_CLICKED ((buttons&EN_C) || (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F1)) #define REPRAPWORLD_KEYPAD_MOVE_Z_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F2) From 6b919e14c1d2986c9d7cd884322fc1b3ad3a5efc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Apr 2015 15:45:41 -0700 Subject: [PATCH 4/7] Group all universal variables --- Marlin/Marlin_main.cpp | 176 +++++++++++++++++------------------------ 1 file changed, 74 insertions(+), 102 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index cc7ac87aa..f82408e5f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -202,10 +202,6 @@ #endif float homing_feedrate[] = HOMING_FEEDRATE; -#ifdef ENABLE_AUTO_BED_LEVELING - int xy_travel_speed = XY_TRAVEL_SPEED; - float zprobe_zoffset = -Z_PROBE_OFFSET_FROM_EXTRUDER; -#endif int homing_bump_divisor[] = HOMING_BUMP_DIVISOR; bool axis_relative_modes[] = AXIS_RELATIVE_MODES; int feedmultiply = 100; //100->1 200->2 @@ -216,15 +212,49 @@ float filament_size[EXTRUDERS] = ARRAY_BY_EXTRUDERS(DEFAULT_NOMINAL_FILAMENT_DIA float volumetric_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS(1.0, 1.0, 1.0, 1.0); float current_position[NUM_AXIS] = { 0.0 }; float home_offset[3] = { 0 }; -#ifdef DELTA - float endstop_adj[3] = { 0 }; -#elif defined(Z_DUAL_ENDSTOPS) - float z_endstop_adj = 0; -#endif - float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }; float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; bool axis_known_position[3] = { false }; +uint8_t active_extruder = 0; +int fanSpeed = 0; +bool cancel_heatup = false; +const char errormagic[] PROGMEM = "Error:"; +const char echomagic[] PROGMEM = "echo:"; +const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'}; +static float destination[NUM_AXIS] = { 0 }; +static float offset[3] = { 0 }; +static float feedrate = 1500.0, next_feedrate, saved_feedrate; +static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0; +static bool relative_mode = false; //Determines Absolute or Relative Coordinates +static char cmdbuffer[BUFSIZE][MAX_CMD_SIZE]; +static int bufindr = 0; +static int bufindw = 0; +static int buflen = 0; +static char serial_char; +static int serial_count = 0; +static boolean comment_mode = false; +static char *strchr_pointer; ///< A pointer to find chars in the command string (X, Y, Z, E, etc.) +const char* queued_commands_P= NULL; /* pointer to the current line in the active sequence of commands, or NULL when none */ +const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42 +// Inactivity shutdown +static unsigned long previous_millis_cmd = 0; +static unsigned long max_inactive_time = 0; +static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l; +unsigned long starttime = 0; ///< Print job start time +unsigned long stoptime = 0; ///< Print job stop time +static uint8_t tmp_extruder; +bool Stopped = false; +bool CooldownNoWait = true; +bool target_direction; + +#ifdef ENABLE_AUTO_BED_LEVELING + int xy_travel_speed = XY_TRAVEL_SPEED; + float zprobe_zoffset = -Z_PROBE_OFFSET_FROM_EXTRUDER; +#endif + +#if defined(Z_DUAL_ENDSTOPS) && !defined(DELTA) + float z_endstop_adj = 0; +#endif // Extruder offsets #if EXTRUDERS > 1 @@ -243,9 +273,6 @@ bool axis_known_position[3] = { false }; }; #endif -uint8_t active_extruder = 0; -int fanSpeed = 0; - #ifdef SERVO_ENDSTOPS int servo_endstops[] = SERVO_ENDSTOPS; int servo_endstop_angles[] = SERVO_ENDSTOP_ANGLES; @@ -282,33 +309,36 @@ int fanSpeed = 0; ; #endif -#ifdef DELTA - float delta[3] = { 0, 0, 0 }; - #define SIN_60 0.8660254037844386 - #define COS_60 0.5 - // 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_tower2_x = SIN_60 * delta_radius; // front right tower - 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; - float delta_diagonal_rod_2 = sq(delta_diagonal_rod); - float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; - #ifdef ENABLE_AUTO_BED_LEVELING - int delta_grid_spacing[2] = { 0, 0 }; - float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS]; +#if defined(DELTA) || defined(SCARA) + static float delta[3] = { 0, 0, 0 }; + #ifdef DELTA + #define SIN_60 0.8660254037844386 + #define COS_60 0.5 + float endstop_adj[3] = { 0 }; + // 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_tower2_x = SIN_60 * delta_radius; // front right tower + 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; + float delta_diagonal_rod_2 = sq(delta_diagonal_rod); + float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; + #ifdef ENABLE_AUTO_BED_LEVELING + int delta_grid_spacing[2] = { 0, 0 }; + float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS]; + #endif #endif -#endif -#ifdef SCARA - float axis_scaling[3] = { 1, 1, 1 }; // Build size scaling, default to 1 - static float delta[3] = { 0, 0, 0 }; -#endif + #ifdef SCARA + float axis_scaling[3] = { 1, 1, 1 }; // Build size scaling, default to 1 + #endif -bool cancel_heatup = false; +#elif !defined(DELTA) + static bool home_all_axis = true; +#endif #ifdef FILAMENT_SENSOR //Variables for Filament Sensor input @@ -326,67 +356,21 @@ bool cancel_heatup = false; static bool filrunoutEnqued = false; #endif -const char errormagic[] PROGMEM = "Error:"; -const char echomagic[] PROGMEM = "echo:"; - -const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'}; -static float destination[NUM_AXIS] = { 0 }; - -static float offset[3] = { 0 }; - -#ifndef DELTA - static bool home_all_axis = true; -#endif - -static float feedrate = 1500.0, next_feedrate, saved_feedrate; -static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0; - -static bool relative_mode = false; //Determines Absolute or Relative Coordinates - -static char cmdbuffer[BUFSIZE][MAX_CMD_SIZE]; #ifdef SDSUPPORT static bool fromsd[BUFSIZE]; #endif -static int bufindr = 0; -static int bufindw = 0; -static int buflen = 0; - -static char serial_char; -static int serial_count = 0; -static boolean comment_mode = false; -static char *strchr_pointer; ///< A pointer to find chars in the command string (X, Y, Z, E, etc.) - -const char* queued_commands_P= NULL; /* pointer to the current line in the active sequence of commands, or NULL when none */ - -const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42 - -// Inactivity shutdown -static unsigned long previous_millis_cmd = 0; -static unsigned long max_inactive_time = 0; -static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l; - -unsigned long starttime = 0; ///< Print job start time -unsigned long stoptime = 0; ///< Print job stop time - -static uint8_t tmp_extruder; - - -bool Stopped = false; #if NUM_SERVOS > 0 Servo servos[NUM_SERVOS]; #endif -bool CooldownNoWait = true; -bool target_direction; - #ifdef CHDK unsigned long chdkHigh = 0; boolean chdkActive = false; #endif //=========================================================================== -//=============================Routines====================================== +//================================ Functions ================================ //=========================================================================== void get_arc_coordinates(); @@ -5707,21 +5691,11 @@ void disable_all_axes() { */ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { - #if HAS_KILL - static int killCount = 0; // make the inactivity button a bit less responsive - const int KILL_DELAY = 750; - #endif - #if HAS_FILRUNOUT if (card.sdprinting && !(READ(FILRUNOUT_PIN) ^ FIL_RUNOUT_INVERTING)) filrunout(); #endif - #if HAS_HOME - static int homeDebounceCount = 0; // poor man's debouncing count - const int HOME_DEBOUNCE_DELAY = 750; - #endif - if (buflen < BUFSIZE - 1) get_command(); unsigned long ms = millis(); @@ -5744,6 +5718,8 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { // Check if the kill button was pressed and wait just in case it was an accidental // key kill key press // ------------------------------------------------------------------------------- + static int killCount = 0; // make the inactivity button a bit less responsive + const int KILL_DELAY = 750; if (!READ(KILL_PIN)) killCount++; else if (killCount > 0) @@ -5758,6 +5734,8 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { #if HAS_HOME // Check to see if we have to home, use poor man's debouncer // --------------------------------------------------------- + static int homeDebounceCount = 0; // poor man's debouncing count + const int HOME_DEBOUNCE_DELAY = 750; if (!READ(HOME_PIN)) { if (!homeDebounceCount) { enquecommands_P(PSTR("G28")); @@ -5797,7 +5775,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { if (delayed_move_time && ms > delayed_move_time + 1000 && !Stopped) { // travel moves have been received so enact them delayed_move_time = 0xFFFFFFFFUL; // force moves to be done - memcpy(destination,current_position, sizeof(destination)); + memcpy(destination, current_position, sizeof(destination)); prepare_move(); } #endif @@ -5814,13 +5792,7 @@ void kill() cli(); // Stop interrupts disable_heater(); - disable_x(); - disable_y(); - disable_z(); - disable_e0(); - disable_e1(); - disable_e2(); - disable_e3(); + disable_all_axes(); #if HAS_POWER_SWITCH pinMode(PS_ON_PIN, INPUT); From 92119d0f7d3ac8f20499585328e52d671556efca Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Apr 2015 16:46:56 -0700 Subject: [PATCH 5/7] Static delta[] for SCARA --- Marlin/Marlin_main.cpp | 52 ++++++++++++++++++++---------------------- 1 file changed, 25 insertions(+), 27 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f82408e5f..113c06e18 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -309,37 +309,35 @@ bool target_direction; ; #endif -#if defined(DELTA) || defined(SCARA) - static float delta[3] = { 0, 0, 0 }; - #ifdef DELTA - #define SIN_60 0.8660254037844386 - #define COS_60 0.5 - float endstop_adj[3] = { 0 }; - // 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_tower2_x = SIN_60 * delta_radius; // front right tower - 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; - float delta_diagonal_rod_2 = sq(delta_diagonal_rod); - float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; - #ifdef ENABLE_AUTO_BED_LEVELING - int delta_grid_spacing[2] = { 0, 0 }; - float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS]; - #endif - #endif - - #ifdef SCARA - float axis_scaling[3] = { 1, 1, 1 }; // Build size scaling, default to 1 +#ifdef DELTA + float delta[3] = { 0 }; + #define SIN_60 0.8660254037844386 + #define COS_60 0.5 + float endstop_adj[3] = { 0 }; + // 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_tower2_x = SIN_60 * delta_radius; // front right tower + 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; + float delta_diagonal_rod_2 = sq(delta_diagonal_rod); + float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; + #ifdef ENABLE_AUTO_BED_LEVELING + int delta_grid_spacing[2] = { 0, 0 }; + float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS]; #endif - -#elif !defined(DELTA) +#else static bool home_all_axis = true; #endif +#ifdef SCARA + static float delta[3] = { 0 }; + float axis_scaling[3] = { 1, 1, 1 }; // Build size scaling, default to 1 +#endif + #ifdef FILAMENT_SENSOR //Variables for Filament Sensor input float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404 From a469d796e16368beef2f5f8e5fbd1aa26e4238bd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Apr 2015 18:14:57 -0700 Subject: [PATCH 6/7] Add cleanups needed for #1772 --- Marlin/Conditionals.h | 1 + Marlin/Configuration.h | 26 +++++++++---------- Marlin/Marlin_main.cpp | 26 +++++++++---------- Marlin/configurator/config/Configuration.h | 14 ++++++++++ .../Felix/Configuration.h | 14 ++++++++++ .../Felix/Configuration_DUAL.h | 14 ++++++++++ .../Hephestos/Configuration.h | 14 ++++++++++ .../K8200/Configuration.h | 14 ++++++++++ .../SCARA/Configuration.h | 14 ++++++++++ .../WITBOX/Configuration.h | 14 ++++++++++ .../delta/generic/Configuration.h | 14 ++++++++++ .../delta/kossel_mini/Configuration.h | 14 ++++++++++ .../makibox/Configuration.h | 14 ++++++++++ .../tvrrug/Round2/Configuration.h | 14 ++++++++++ 14 files changed, 181 insertions(+), 26 deletions(-) diff --git a/Marlin/Conditionals.h b/Marlin/Conditionals.h index 8e50deee5..5d3213e0e 100644 --- a/Marlin/Conditionals.h +++ b/Marlin/Conditionals.h @@ -389,6 +389,7 @@ #define HAS_Z_MAX (PIN_EXISTS(Z_MAX)) #define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN)) #define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX)) + #define HAS_Z_PROBE (PIN_EXISTS(Z_PROBE)) #define HAS_SOLENOID_1 (PIN_EXISTS(SOL1)) #define HAS_SOLENOID_2 (PIN_EXISTS(SOL2)) #define HAS_SOLENOID_3 (PIN_EXISTS(SOL3)) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 4dd2d1020..321c25f97 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -499,19 +499,19 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic #endif -// Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. -// If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. -// If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. -// WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. -// To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. -// If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. -// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 -// for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. -// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. -// D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. -// WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. - -// #define Z_PROBE_ENDSTOP + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index e5261e85c..f9a1ed60b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1226,13 +1226,14 @@ inline void sync_plan_position() { st_synchronize(); - #if defined(Z_PROBE_ENDSTOP) + #ifdef Z_PROBE_ENDSTOP bool z_probe_endstop = (READ(Z_PROBE_PIN) != Z_PROBE_ENDSTOP_INVERTING); - if (z_probe_endstop) { + if (z_probe_endstop) #else bool z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING); - if (z_min_endstop) { + if (z_min_endstop) #endif + { if (!Stopped) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM("Z-Probe failed to engage!"); @@ -1300,13 +1301,14 @@ inline void sync_plan_position() { st_synchronize(); - #if defined(Z_PROBE_ENDSTOP) + #ifdef Z_PROBE_ENDSTOP bool z_probe_endstop = (READ(Z_PROBE_PIN) != Z_PROBE_ENDSTOP_INVERTING); - if (!z_probe_endstop) { + if (!z_probe_endstop) #else bool z_min_endstop = (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING); - if (!z_min_endstop) { + if (!z_min_endstop) #endif + { if (!Stopped) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM("Z-Probe failed to retract!"); @@ -2778,14 +2780,12 @@ inline void gcode_M42() { #if defined(ENABLE_AUTO_BED_LEVELING) && defined(Z_PROBE_REPEATABILITY_TEST) // This is redudant since the SanityCheck.h already checks for a valid Z_PROBE_PIN, but here for clarity. - #if defined (Z_PROBE_ENDSTOP) - #if (! defined (Z_PROBE_PIN) || Z_PROBE_PIN == -1) + #ifdef Z_PROBE_ENDSTOP + #if !HAS_Z_PROBE #error "You must have a Z_PROBE_PIN defined in order to enable calculation of Z-Probe repeatability." #endif - #else - #if (Z_MIN_PIN == -1) - #error "You must have a Z_MIN_PIN defined in order to enable calculation of Z-Probe repeatability." - #endif + #elif !HAS_Z_MIN + #error "You must have a Z_MIN_PIN defined in order to enable calculation of Z-Probe repeatability." #endif /** @@ -3515,7 +3515,7 @@ inline void gcode_M119() { SERIAL_PROTOCOLPGM(MSG_Z2_MAX); SERIAL_PROTOCOLLN(((READ(Z2_MAX_PIN)^Z2_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif - #if defined(Z_PROBE_PIN) && Z_PROBE_PIN > -1 + #if HAS_Z_PROBE SERIAL_PROTOCOLPGM(MSG_Z_PROBE); SERIAL_PROTOCOLLN(((READ(Z_PROBE_PIN)^Z_PROBE_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN)); #endif diff --git a/Marlin/configurator/config/Configuration.h b/Marlin/configurator/config/Configuration.h index 3e1a56dc4..3d9f63424 100644 --- a/Marlin/configurator/config/Configuration.h +++ b/Marlin/configurator/config/Configuration.h @@ -519,6 +519,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 4c8353823..7f0b03049 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -469,6 +469,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/Felix/Configuration_DUAL.h b/Marlin/example_configurations/Felix/Configuration_DUAL.h index a0ecacd92..fbb144514 100644 --- a/Marlin/example_configurations/Felix/Configuration_DUAL.h +++ b/Marlin/example_configurations/Felix/Configuration_DUAL.h @@ -469,6 +469,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index e66222346..366576021 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -492,6 +492,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 854367af8..7ddf21e2b 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -497,6 +497,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 15fde93f8..a00a7b6e9 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -521,6 +521,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 5bccb9827..902985f31 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -491,6 +491,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 1403ddd2d..699b8a3b4 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -537,6 +537,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 420dfa9e4..2e4ebb386 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -541,6 +541,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 55e26ebf8..5c8e1d87d 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -489,6 +489,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 6b781b7a4..12bab57e3 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -491,6 +491,20 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of #endif + // Support for a dedicated Z PROBE endstop separate from the Z MIN endstop. + // If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below. + // If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28. + // WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print. + // To use a separte Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board. + // If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below. + // RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32 + // for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed. + // The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works. + // D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file. + // WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework. + + //#define Z_PROBE_ENDSTOP + #endif // ENABLE_AUTO_BED_LEVELING From abd7fc36b68796413ca421a3e9d30bec93a7cdcf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Apr 2015 18:54:55 -0700 Subject: [PATCH 7/7] Fix probe height at G28 start --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f9a1ed60b..f160f07a4 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2306,7 +2306,7 @@ inline void gcode_G28() { // raise extruder float measured_z, - z_before = Z_RAISE_BETWEEN_PROBINGS + (probePointCounter ? current_position[Z_AXIS] : 0); + z_before = probePointCounter ? Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS] : Z_RAISE_BEFORE_PROBING; #ifdef DELTA // Avoid probing the corners (outside the round or hexagon print surface) on a delta printer.