Merge pull request #80 from alexrj/different-endstops

Change ENDSTOPS_INVERTING to [XYZ]_ENDSTOP_INVERT
This commit is contained in:
kliment 2011-09-08 12:29:29 -07:00
commit 7dd34fc5e8
2 changed files with 22 additions and 20 deletions

View file

@ -35,9 +35,11 @@ float axis_steps_per_unit[] = {80, 80, 3200/1.25,700};
//// Endstop Settings //// Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins. // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
const bool ENDSTOPS_INVERTING = false; //set to true to invert the logic of the endstops
//If your axes are only moving in one direction, make sure the endstops are connected properly. //If your axes are only moving in one direction, make sure the endstops are connected properly.
//If your axes move in one direction ONLY when the endstops are triggered, set ENDSTOPS_INVERTING to true here //If your axes move in one direction ONLY when the endstops are triggered, set [XYZ]_ENDSTOP_INVERT to true here:
const bool X_ENDSTOP_INVERT = false;
const bool Y_ENDSTOP_INVERT = false;
const bool Z_ENDSTOP_INVERT = false;
// This determines the communication speed of the printer // This determines the communication speed of the printer
#define BAUDRATE 115200 #define BAUDRATE 115200

View file

@ -909,27 +909,27 @@ inline void process_commands()
case 119: // M119 case 119: // M119
#if (X_MIN_PIN > -1) #if (X_MIN_PIN > -1)
Serial.print("x_min:"); Serial.print("x_min:");
Serial.print((READ(X_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L "); Serial.print((READ(X_MIN_PIN)^X_ENDSTOP_INVERT)?"H ":"L ");
#endif #endif
#if (X_MAX_PIN > -1) #if (X_MAX_PIN > -1)
Serial.print("x_max:"); Serial.print("x_max:");
Serial.print((READ(X_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L "); Serial.print((READ(X_MAX_PIN)^X_ENDSTOP_INVERT)?"H ":"L ");
#endif #endif
#if (Y_MIN_PIN > -1) #if (Y_MIN_PIN > -1)
Serial.print("y_min:"); Serial.print("y_min:");
Serial.print((READ(Y_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L "); Serial.print((READ(Y_MIN_PIN)^Y_ENDSTOP_INVERT)?"H ":"L ");
#endif #endif
#if (Y_MAX_PIN > -1) #if (Y_MAX_PIN > -1)
Serial.print("y_max:"); Serial.print("y_max:");
Serial.print((READ(Y_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L "); Serial.print((READ(Y_MAX_PIN)^Y_ENDSTOP_INVERT)?"H ":"L ");
#endif #endif
#if (Z_MIN_PIN > -1) #if (Z_MIN_PIN > -1)
Serial.print("z_min:"); Serial.print("z_min:");
Serial.print((READ(Z_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L "); Serial.print((READ(Z_MIN_PIN)^Z_ENDSTOP_INVERT)?"H ":"L ");
#endif #endif
#if (Z_MAX_PIN > -1) #if (Z_MAX_PIN > -1)
Serial.print("z_max:"); Serial.print("z_max:");
Serial.print((READ(Z_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L "); Serial.print((READ(Z_MAX_PIN)^Z_ENDSTOP_INVERT)?"H ":"L ");
#endif #endif
Serial.println(""); Serial.println("");
break; break;
@ -1084,22 +1084,22 @@ inline void linear_move(unsigned long axis_steps_remaining[]) // make linear mov
else WRITE(E_DIR_PIN,INVERT_E_DIR); else WRITE(E_DIR_PIN,INVERT_E_DIR);
movereset: movereset:
#if (X_MIN_PIN > -1) #if (X_MIN_PIN > -1)
if(!move_direction[0]) if(READ(X_MIN_PIN) != ENDSTOPS_INVERTING) axis_steps_remaining[0]=0; if(!move_direction[0]) if(READ(X_MIN_PIN) != X_ENDSTOP_INVERT) axis_steps_remaining[0]=0;
#endif #endif
#if (Y_MIN_PIN > -1) #if (Y_MIN_PIN > -1)
if(!move_direction[1]) if(READ(Y_MIN_PIN) != ENDSTOPS_INVERTING) axis_steps_remaining[1]=0; if(!move_direction[1]) if(READ(Y_MIN_PIN) != Y_ENDSTOP_INVERT) axis_steps_remaining[1]=0;
#endif #endif
#if (Z_MIN_PIN > -1) #if (Z_MIN_PIN > -1)
if(!move_direction[2]) if(READ(Z_MIN_PIN) != ENDSTOPS_INVERTING) axis_steps_remaining[2]=0; if(!move_direction[2]) if(READ(Z_MIN_PIN) != Z_ENDSTOP_INVERT) axis_steps_remaining[2]=0;
#endif #endif
#if (X_MAX_PIN > -1) #if (X_MAX_PIN > -1)
if(move_direction[0]) if(READ(X_MAX_PIN) != ENDSTOPS_INVERTING) axis_steps_remaining[0]=0; if(move_direction[0]) if(READ(X_MAX_PIN) != X_ENDSTOP_INVERT) axis_steps_remaining[0]=0;
#endif #endif
#if (Y_MAX_PIN > -1) #if (Y_MAX_PIN > -1)
if(move_direction[1]) if(READ(Y_MAX_PIN) != ENDSTOPS_INVERTING) axis_steps_remaining[1]=0; if(move_direction[1]) if(READ(Y_MAX_PIN) != Y_ENDSTOP_INVERT) axis_steps_remaining[1]=0;
#endif #endif
# if(Z_MAX_PIN > -1) # if(Z_MAX_PIN > -1)
if(move_direction[2]) if(READ(Z_MAX_PIN) != ENDSTOPS_INVERTING) axis_steps_remaining[2]=0; if(move_direction[2]) if(READ(Z_MAX_PIN) != Z_ENDSTOP_INVERT) axis_steps_remaining[2]=0;
#endif #endif
@ -1275,22 +1275,22 @@ inline void linear_move(unsigned long axis_steps_remaining[]) // make linear mov
//If there are x or y steps remaining, perform Bresenham algorithm //If there are x or y steps remaining, perform Bresenham algorithm
if(axis_steps_remaining[primary_axis]) { if(axis_steps_remaining[primary_axis]) {
#if (X_MIN_PIN > -1) #if (X_MIN_PIN > -1)
if(!move_direction[0]) if(READ(X_MIN_PIN) != ENDSTOPS_INVERTING) if(primary_axis==0) break; else if(axis_steps_remaining[0]) axis_steps_remaining[0]=0; if(!move_direction[0]) if(READ(X_MIN_PIN) != X_ENDSTOP_INVERT) if(primary_axis==0) break; else if(axis_steps_remaining[0]) axis_steps_remaining[0]=0;
#endif #endif
#if (Y_MIN_PIN > -1) #if (Y_MIN_PIN > -1)
if(!move_direction[1]) if(READ(Y_MIN_PIN) != ENDSTOPS_INVERTING) if(primary_axis==1) break; else if(axis_steps_remaining[1]) axis_steps_remaining[1]=0; if(!move_direction[1]) if(READ(Y_MIN_PIN) != Y_ENDSTOP_INVERT) if(primary_axis==1) break; else if(axis_steps_remaining[1]) axis_steps_remaining[1]=0;
#endif #endif
#if (X_MAX_PIN > -1) #if (X_MAX_PIN > -1)
if(move_direction[0]) if(READ(X_MAX_PIN) != ENDSTOPS_INVERTING) if(primary_axis==0) break; else if(axis_steps_remaining[0]) axis_steps_remaining[0]=0; if(move_direction[0]) if(READ(X_MAX_PIN) != X_ENDSTOP_INVERT) if(primary_axis==0) break; else if(axis_steps_remaining[0]) axis_steps_remaining[0]=0;
#endif #endif
#if (Y_MAX_PIN > -1) #if (Y_MAX_PIN > -1)
if(move_direction[1]) if(READ(Y_MAX_PIN) != ENDSTOPS_INVERTING) if(primary_axis==1) break; else if(axis_steps_remaining[1]) axis_steps_remaining[1]=0; if(move_direction[1]) if(READ(Y_MAX_PIN) != Y_ENDSTOP_INVERT) if(primary_axis==1) break; else if(axis_steps_remaining[1]) axis_steps_remaining[1]=0;
#endif #endif
#if (Z_MIN_PIN > -1) #if (Z_MIN_PIN > -1)
if(!move_direction[2]) if(READ(Z_MIN_PIN) != ENDSTOPS_INVERTING) if(primary_axis==2) break; else if(axis_steps_remaining[2]) axis_steps_remaining[2]=0; if(!move_direction[2]) if(READ(Z_MIN_PIN) != Z_ENDSTOP_INVERT) if(primary_axis==2) break; else if(axis_steps_remaining[2]) axis_steps_remaining[2]=0;
#endif #endif
#if (Z_MAX_PIN > -1) #if (Z_MAX_PIN > -1)
if(move_direction[2]) if(READ(Z_MAX_PIN) != ENDSTOPS_INVERTING) if(primary_axis==2) break; else if(axis_steps_remaining[2]) axis_steps_remaining[2]=0; if(move_direction[2]) if(READ(Z_MAX_PIN) != Z_ENDSTOP_INVERT) if(primary_axis==2) break; else if(axis_steps_remaining[2]) axis_steps_remaining[2]=0;
#endif #endif
timediff = micros() * 100 - axis_previous_micros[primary_axis]; timediff = micros() * 100 - axis_previous_micros[primary_axis];
if(timediff<0){//check for overflow if(timediff<0){//check for overflow