Pulldown pin mode support (#9701)

Implemented for LPC1768.
This commit is contained in:
Scott Lahteine 2018-02-18 19:26:23 -06:00 committed by GitHub
parent aef9e036bf
commit ca55f2927a
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
66 changed files with 1182 additions and 325 deletions

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -71,7 +71,7 @@ extern "C" void delay(const int msec) {
// IO functions // IO functions
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2) // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
void pinMode(pin_t pin, uint8_t mode) { void pinMode(const pin_t pin, const uint8_t mode) {
if (!VALID_PIN(pin)) return; if (!VALID_PIN(pin)) return;
PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin), PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
@ -79,23 +79,24 @@ void pinMode(pin_t pin, uint8_t mode) {
PINSEL_FUNC_0, PINSEL_FUNC_0,
PINSEL_PINMODE_TRISTATE, PINSEL_PINMODE_TRISTATE,
PINSEL_PINMODE_NORMAL }; PINSEL_PINMODE_NORMAL };
switch(mode) { switch (mode) {
case INPUT: case INPUT:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin)); LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
PINSEL_ConfigPin(&config);
break; break;
case OUTPUT: case OUTPUT:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin)); LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin));
PINSEL_ConfigPin(&config);
break; break;
case INPUT_PULLUP: case INPUT_PULLUP:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin)); LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
config.Pinmode = PINSEL_PINMODE_PULLUP; config.Pinmode = PINSEL_PINMODE_PULLUP;
PINSEL_ConfigPin(&config);
break; break;
default: case INPUT_PULLDOWN:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
config.Pinmode = PINSEL_PINMODE_PULLDOWN;
break; break;
default: return;
} }
PINSEL_ConfigPin(&config);
} }
void digitalWrite(pin_t pin, uint8_t pin_status) { void digitalWrite(pin_t pin, uint8_t pin_status) {

View file

@ -85,6 +85,9 @@ bool useable_hardware_PWM(pin_t pin);
/// set pin as input with pullup mode /// set pin as input with pullup mode
#define _PULLUP(IO, v) (pinMode(IO, (v!=LOW ? INPUT_PULLUP : INPUT))) #define _PULLUP(IO, v) (pinMode(IO, (v!=LOW ? INPUT_PULLUP : INPUT)))
/// set pin as input with pulldown mode
#define _PULLDOWN(IO, v) (pinMode(IO, (v!=LOW ? INPUT_PULLDOWN : INPUT)))
// hg42: all pins can be input or output (I hope) // hg42: all pins can be input or output (I hope)
// hg42: undefined pins create compile error (IO, is no pin) // hg42: undefined pins create compile error (IO, is no pin)
// hg42: currently not used, but was used by pinsDebug // hg42: currently not used, but was used by pinsDebug
@ -119,6 +122,8 @@ bool useable_hardware_PWM(pin_t pin);
#define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT(IO) _SET_INPUT(IO)
/// set pin as input with pullup wrapper /// set pin as input with pullup wrapper
#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0) #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
/// set pin as input with pulldown wrapper
#define SET_INPUT_PULLDOWN(IO) do{ _SET_INPUT(IO); _PULLDOWN(IO, HIGH); }while(0)
/// set pin as output wrapper - reads the pin and sets the output to that value /// set pin as output wrapper - reads the pin and sets the output to that value
#define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0) #define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0)

View file

@ -34,6 +34,7 @@
#define INPUT 0x00 #define INPUT 0x00
#define OUTPUT 0x01 #define OUTPUT 0x01
#define INPUT_PULLUP 0x02 #define INPUT_PULLUP 0x02
#define INPUT_PULLDOWN 0x03
#define LSBFIRST 0 #define LSBFIRST 0
#define MSBFIRST 1 #define MSBFIRST 1
@ -104,7 +105,7 @@ void delayMicroseconds(unsigned long);
uint32_t millis(); uint32_t millis();
//IO functions //IO functions
void pinMode(pin_t, uint8_t); void pinMode(const pin_t, const uint8_t);
void digitalWrite(pin_t, uint8_t); void digitalWrite(pin_t, uint8_t);
bool digitalRead(pin_t); bool digitalRead(pin_t);
void analogWrite(pin_t, int); void analogWrite(pin_t, int);

View file

@ -219,8 +219,10 @@ void setup_killpin() {
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
void setup_filrunoutpin() { void setup_filrunoutpin() {
#if ENABLED(ENDSTOPPULLUP_FIL_RUNOUT) #if ENABLED(FIL_RUNOUT_PULLUP)
SET_INPUT_PULLUP(FIL_RUNOUT_PIN); SET_INPUT_PULLUP(FIL_RUNOUT_PIN);
#elif ENABLED(FIL_RUNOUT_PULLDOWN)
SET_INPUT_PULLDOWN(FIL_RUNOUT_PIN);
#else #else
SET_INPUT(FIL_RUNOUT_PIN); SET_INPUT(FIL_RUNOUT_PIN);
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -520,11 +520,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -534,6 +533,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -870,7 +882,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -520,11 +520,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -534,6 +533,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -960,7 +972,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -507,11 +507,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -521,6 +520,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -857,7 +869,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop. const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop. const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop. const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop. const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -488,11 +488,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -502,6 +501,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -838,7 +850,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -501,11 +501,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -515,6 +514,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -851,7 +863,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -488,11 +488,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -502,6 +501,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -838,7 +850,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -499,11 +499,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -513,6 +512,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -849,7 +861,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -510,11 +510,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors //#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -524,6 +523,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -860,7 +872,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -491,11 +491,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -505,6 +504,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -841,7 +853,8 @@
#define FILAMENT_RUNOUT_SENSOR #define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING true // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING true // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#define FIL_RUNOUT_PIN 2 // Creality CR10-S stock sensor #define FIL_RUNOUT_PIN 2 // Creality CR10-S stock sensor
#endif #endif

View file

@ -495,11 +495,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -509,6 +508,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -845,7 +857,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -481,11 +481,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -495,6 +494,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -832,7 +844,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -481,11 +481,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -495,6 +494,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -832,7 +844,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -506,11 +506,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -520,6 +519,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -856,7 +868,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -515,11 +515,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -529,6 +528,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -865,7 +877,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -506,11 +506,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -520,6 +519,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -857,7 +869,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -506,11 +506,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -520,6 +519,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -856,7 +868,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -504,11 +504,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -518,6 +517,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -854,7 +866,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -512,11 +512,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -526,6 +525,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -862,7 +874,8 @@
#define FILAMENT_RUNOUT_SENSOR #define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -520,11 +520,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
#define ENDSTOPPULLUP_XMAX #define ENDSTOPPULLUP_XMAX
#define ENDSTOPPULLUP_YMAX #define ENDSTOPPULLUP_YMAX
#define ENDSTOPPULLUP_ZMAX #define ENDSTOPPULLUP_ZMAX
@ -534,6 +533,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -870,7 +882,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -508,11 +508,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -522,6 +521,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -874,7 +886,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -499,11 +499,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -513,6 +512,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -849,7 +861,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -854,7 +866,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -854,7 +866,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -496,11 +496,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -510,6 +509,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -848,7 +860,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -512,11 +512,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors //#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
#define ENDSTOPPULLUP_ZMAX // open pin, inverted #define ENDSTOPPULLUP_ZMAX // open pin, inverted
@ -526,6 +525,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -862,7 +874,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -502,11 +502,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -516,6 +515,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -853,7 +865,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -881,7 +893,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -551,11 +551,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -565,6 +564,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -906,7 +918,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -491,11 +491,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -505,6 +504,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -841,7 +853,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -511,11 +511,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -525,6 +524,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -861,7 +873,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -491,11 +491,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -505,6 +504,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -841,7 +853,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -530,11 +530,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -544,6 +543,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -880,7 +892,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -501,11 +501,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -515,6 +514,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -851,7 +863,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -500,11 +500,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -514,6 +513,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -850,7 +862,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -579,11 +579,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -593,6 +592,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -980,7 +992,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -570,11 +570,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -584,6 +583,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -971,7 +983,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -579,11 +579,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -593,6 +592,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -980,7 +992,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -569,11 +569,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -583,6 +582,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -967,7 +979,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -569,11 +569,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -583,6 +582,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -970,7 +982,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -555,11 +555,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -569,6 +568,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -970,7 +982,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -573,11 +573,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors //#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
#define ENDSTOPPULLUP_XMAX #define ENDSTOPPULLUP_XMAX
#define ENDSTOPPULLUP_YMAX #define ENDSTOPPULLUP_YMAX
#define ENDSTOPPULLUP_ZMAX #define ENDSTOPPULLUP_ZMAX
@ -587,6 +586,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -979,7 +991,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -513,11 +513,10 @@
#define USE_YMAX_PLUG #define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors //#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -527,6 +526,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -864,7 +876,8 @@
#define FILAMENT_RUNOUT_SENSOR #define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -503,11 +503,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -517,6 +516,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -853,7 +865,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -502,11 +502,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -516,6 +515,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
@ -851,7 +863,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -489,11 +489,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG //#define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -503,6 +502,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -845,7 +857,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -505,11 +505,10 @@
//#define USE_YMAX_PLUG //#define USE_YMAX_PLUG
#define USE_ZMAX_PLUG #define USE_ZMAX_PLUG
// coarse Endstop Settings // Enable pullup for all endstops to prevent a floating state
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS) #if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined // Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_ZMAX
@ -519,6 +518,19 @@
//#define ENDSTOPPULLUP_ZMIN_PROBE //#define ENDSTOPPULLUP_ZMIN_PROBE
#endif #endif
// Enable pulldown for all endstops to prevent a floating state
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
@ -855,7 +867,8 @@
//#define FILAMENT_RUNOUT_SENSOR //#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR) #if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor. #define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
//#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600" #define FILAMENT_RUNOUT_SCRIPT "M600"
#endif #endif

View file

@ -616,6 +616,30 @@
#endif #endif
#endif #endif
/**
* Set ENDSTOPPULLDOWNS for active endstop switches
*/
#if ENABLED(ENDSTOPPULLDOWNS)
#if ENABLED(USE_XMAX_PLUG)
#define ENDSTOPPULLDOWN_XMAX
#endif
#if ENABLED(USE_YMAX_PLUG)
#define ENDSTOPPULLDOWN_YMAX
#endif
#if ENABLED(USE_ZMAX_PLUG)
#define ENDSTOPPULLDOWN_ZMAX
#endif
#if ENABLED(USE_XMIN_PLUG)
#define ENDSTOPPULLDOWN_XMIN
#endif
#if ENABLED(USE_YMIN_PLUG)
#define ENDSTOPPULLDOWN_YMIN
#endif
#if ENABLED(USE_ZMIN_PLUG)
#define ENDSTOPPULLDOWN_ZMIN
#endif
#endif
/** /**
* Shorthand for pin tests, used wherever needed * Shorthand for pin tests, used wherever needed
*/ */

View file

@ -78,7 +78,9 @@
#elif defined(SDEXTRASLOW) #elif defined(SDEXTRASLOW)
#error "SDEXTRASLOW deprecated. Set SPI_SPEED to SPI_QUARTER_SPEED instead." #error "SDEXTRASLOW deprecated. Set SPI_SPEED to SPI_QUARTER_SPEED instead."
#elif defined(FILAMENT_SENSOR) #elif defined(FILAMENT_SENSOR)
#error "FILAMENT_SENSOR is deprecated. Use FILAMENT_WIDTH_SENSOR instead." #error "FILAMENT_SENSOR is now FILAMENT_WIDTH_SENSOR. Please update your configuration."
#elif defined(ENDSTOPPULLUP_FIL_RUNOUT)
#error "ENDSTOPPULLUP_FIL_RUNOUT is now FIL_RUNOUT_PULLUP. Please update your configuration."
#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS) #elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS)
#error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead." #error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead."
#elif defined(LANGUAGE_INCLUDE) #elif defined(LANGUAGE_INCLUDE)
@ -323,6 +325,35 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#endif #endif
#endif #endif
#if !defined(TARGET_LPC1768) && ( \
ENABLED(ENDSTOPPULLDOWNS) \
|| ENABLED(ENDSTOPPULLDOWN_XMAX) \
|| ENABLED(ENDSTOPPULLDOWN_YMAX) \
|| ENABLED(ENDSTOPPULLDOWN_ZMAX) \
|| ENABLED(ENDSTOPPULLDOWN_XMIN) \
|| ENABLED(ENDSTOPPULLDOWN_YMIN) \
|| ENABLED(ENDSTOPPULLDOWN_ZMIN) )
#error "PULLDOWN pin mode is not available on the selected board."
#endif
#if ENABLED(ENDSTOPPULLUPS) && ENABLED(ENDSTOPPULLDOWNS)
#error "Enable only one of ENDSTOPPULLUPS or ENDSTOPPULLDOWNS."
#elif ENABLED(FIL_RUNOUT_PULLUP) && ENABLED(FIL_RUNOUT_PULLDOWN)
#error "Enable only one of FIL_RUNOUT_PULLUP or FIL_RUNOUT_PULLDOWN."
#elif ENABLED(ENDSTOPPULLUP_XMAX) && ENABLED(ENDSTOPPULLDOWN_XMAX)
#error "Enable only one of ENDSTOPPULLUP_X_MAX or ENDSTOPPULLDOWN_X_MAX."
#elif ENABLED(ENDSTOPPULLUP_YMAX) && ENABLED(ENDSTOPPULLDOWN_YMAX)
#error "Enable only one of ENDSTOPPULLUP_Y_MAX or ENDSTOPPULLDOWN_Y_MAX."
#elif ENABLED(ENDSTOPPULLUP_ZMAX) && ENABLED(ENDSTOPPULLDOWN_ZMAX)
#error "Enable only one of ENDSTOPPULLUP_Z_MAX or ENDSTOPPULLDOWN_Z_MAX."
#elif ENABLED(ENDSTOPPULLUP_XMIN) && ENABLED(ENDSTOPPULLDOWN_XMIN)
#error "Enable only one of ENDSTOPPULLUP_X_MIN or ENDSTOPPULLDOWN_X_MIN."
#elif ENABLED(ENDSTOPPULLUP_YMIN) && ENABLED(ENDSTOPPULLDOWN_YMIN)
#error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN."
#elif ENABLED(ENDSTOPPULLUP_ZMIN) && ENABLED(ENDSTOPPULLDOWN_ZMIN)
#error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN."
#endif
/** /**
* Progress Bar * Progress Bar
*/ */

View file

@ -73,6 +73,8 @@ void Endstops::init() {
#if HAS_X_MIN #if HAS_X_MIN
#if ENABLED(ENDSTOPPULLUP_XMIN) #if ENABLED(ENDSTOPPULLUP_XMIN)
SET_INPUT_PULLUP(X_MIN_PIN); SET_INPUT_PULLUP(X_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_XMIN)
SET_INPUT_PULLDOWN(X_MIN_PIN);
#else #else
SET_INPUT(X_MIN_PIN); SET_INPUT(X_MIN_PIN);
#endif #endif
@ -81,6 +83,8 @@ void Endstops::init() {
#if HAS_X2_MIN #if HAS_X2_MIN
#if ENABLED(ENDSTOPPULLUP_XMIN) #if ENABLED(ENDSTOPPULLUP_XMIN)
SET_INPUT_PULLUP(X2_MIN_PIN); SET_INPUT_PULLUP(X2_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_XMIN)
SET_INPUT_PULLDOWN(X2_MIN_PIN);
#else #else
SET_INPUT(X2_MIN_PIN); SET_INPUT(X2_MIN_PIN);
#endif #endif
@ -89,6 +93,8 @@ void Endstops::init() {
#if HAS_Y_MIN #if HAS_Y_MIN
#if ENABLED(ENDSTOPPULLUP_YMIN) #if ENABLED(ENDSTOPPULLUP_YMIN)
SET_INPUT_PULLUP(Y_MIN_PIN); SET_INPUT_PULLUP(Y_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_YMIN)
SET_INPUT_PULLDOWN(Y_MIN_PIN);
#else #else
SET_INPUT(Y_MIN_PIN); SET_INPUT(Y_MIN_PIN);
#endif #endif
@ -97,6 +103,8 @@ void Endstops::init() {
#if HAS_Y2_MIN #if HAS_Y2_MIN
#if ENABLED(ENDSTOPPULLUP_YMIN) #if ENABLED(ENDSTOPPULLUP_YMIN)
SET_INPUT_PULLUP(Y2_MIN_PIN); SET_INPUT_PULLUP(Y2_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_YMIN)
SET_INPUT_PULLDOWN(Y2_MIN_PIN);
#else #else
SET_INPUT(Y2_MIN_PIN); SET_INPUT(Y2_MIN_PIN);
#endif #endif
@ -105,6 +113,8 @@ void Endstops::init() {
#if HAS_Z_MIN #if HAS_Z_MIN
#if ENABLED(ENDSTOPPULLUP_ZMIN) #if ENABLED(ENDSTOPPULLUP_ZMIN)
SET_INPUT_PULLUP(Z_MIN_PIN); SET_INPUT_PULLUP(Z_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMIN)
SET_INPUT_PULLDOWN(Z_MIN_PIN);
#else #else
SET_INPUT(Z_MIN_PIN); SET_INPUT(Z_MIN_PIN);
#endif #endif
@ -113,6 +123,8 @@ void Endstops::init() {
#if HAS_Z2_MIN #if HAS_Z2_MIN
#if ENABLED(ENDSTOPPULLUP_ZMIN) #if ENABLED(ENDSTOPPULLUP_ZMIN)
SET_INPUT_PULLUP(Z2_MIN_PIN); SET_INPUT_PULLUP(Z2_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMIN)
SET_INPUT_PULLDOWN(Z2_MIN_PIN);
#else #else
SET_INPUT(Z2_MIN_PIN); SET_INPUT(Z2_MIN_PIN);
#endif #endif
@ -121,6 +133,8 @@ void Endstops::init() {
#if HAS_X_MAX #if HAS_X_MAX
#if ENABLED(ENDSTOPPULLUP_XMAX) #if ENABLED(ENDSTOPPULLUP_XMAX)
SET_INPUT_PULLUP(X_MAX_PIN); SET_INPUT_PULLUP(X_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_XMAX)
SET_INPUT_PULLDOWN(X_MAX_PIN);
#else #else
SET_INPUT(X_MAX_PIN); SET_INPUT(X_MAX_PIN);
#endif #endif
@ -129,6 +143,8 @@ void Endstops::init() {
#if HAS_X2_MAX #if HAS_X2_MAX
#if ENABLED(ENDSTOPPULLUP_XMAX) #if ENABLED(ENDSTOPPULLUP_XMAX)
SET_INPUT_PULLUP(X2_MAX_PIN); SET_INPUT_PULLUP(X2_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_XMAX)
SET_INPUT_PULLDOWN(X2_MAX_PIN);
#else #else
SET_INPUT(X2_MAX_PIN); SET_INPUT(X2_MAX_PIN);
#endif #endif
@ -137,6 +153,8 @@ void Endstops::init() {
#if HAS_Y_MAX #if HAS_Y_MAX
#if ENABLED(ENDSTOPPULLUP_YMAX) #if ENABLED(ENDSTOPPULLUP_YMAX)
SET_INPUT_PULLUP(Y_MAX_PIN); SET_INPUT_PULLUP(Y_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_YMAX)
SET_INPUT_PULLDOWN(Y_MAX_PIN);
#else #else
SET_INPUT(Y_MAX_PIN); SET_INPUT(Y_MAX_PIN);
#endif #endif
@ -145,6 +163,8 @@ void Endstops::init() {
#if HAS_Y2_MAX #if HAS_Y2_MAX
#if ENABLED(ENDSTOPPULLUP_YMAX) #if ENABLED(ENDSTOPPULLUP_YMAX)
SET_INPUT_PULLUP(Y2_MAX_PIN); SET_INPUT_PULLUP(Y2_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_YMAX)
SET_INPUT_PULLDOWN(Y2_MAX_PIN);
#else #else
SET_INPUT(Y2_MAX_PIN); SET_INPUT(Y2_MAX_PIN);
#endif #endif
@ -153,6 +173,8 @@ void Endstops::init() {
#if HAS_Z_MAX #if HAS_Z_MAX
#if ENABLED(ENDSTOPPULLUP_ZMAX) #if ENABLED(ENDSTOPPULLUP_ZMAX)
SET_INPUT_PULLUP(Z_MAX_PIN); SET_INPUT_PULLUP(Z_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMAX)
SET_INPUT_PULLDOWN(Z_MAX_PIN);
#else #else
SET_INPUT(Z_MAX_PIN); SET_INPUT(Z_MAX_PIN);
#endif #endif
@ -161,6 +183,8 @@ void Endstops::init() {
#if HAS_Z2_MAX #if HAS_Z2_MAX
#if ENABLED(ENDSTOPPULLUP_ZMAX) #if ENABLED(ENDSTOPPULLUP_ZMAX)
SET_INPUT_PULLUP(Z2_MAX_PIN); SET_INPUT_PULLUP(Z2_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMAX)
SET_INPUT_PULLDOWN(Z2_MAX_PIN);
#else #else
SET_INPUT(Z2_MAX_PIN); SET_INPUT(Z2_MAX_PIN);
#endif #endif
@ -169,6 +193,8 @@ void Endstops::init() {
#if ENABLED(Z_MIN_PROBE_ENDSTOP) #if ENABLED(Z_MIN_PROBE_ENDSTOP)
#if ENABLED(ENDSTOPPULLUP_ZMIN_PROBE) #if ENABLED(ENDSTOPPULLUP_ZMIN_PROBE)
SET_INPUT_PULLUP(Z_MIN_PROBE_PIN); SET_INPUT_PULLUP(Z_MIN_PROBE_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMIN_PROBE)
SET_INPUT_PULLDOWN(Z_MIN_PROBE_PIN);
#else #else
SET_INPUT(Z_MIN_PROBE_PIN); SET_INPUT(Z_MIN_PROBE_PIN);
#endif #endif