mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2024-11-23 12:04:19 +00:00
Additional pin tests, cleanup
This commit is contained in:
parent
93fdc2951b
commit
0e8182bbf2
@ -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
|
||||
|
@ -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.
|
||||
|
@ -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);
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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]);
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -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
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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) {
|
||||
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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
|
||||
|
@ -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.
|
||||
|
||||
|
@ -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))
|
||||
|
@ -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
|
||||
|
@ -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));
|
||||
|
@ -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
|
||||
|
||||
|
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user