Browse Source

Additional pin tests, cleanup

Scott Lahteine 9 years ago
parent
commit
0e8182bbf2
34 changed files with 603 additions and 576 deletions
  1. 75
    18
      Marlin/Conditionals.h
  2. 2
    2
      Marlin/Configuration.h
  3. 2
    2
      Marlin/ConfigurationStore.cpp
  4. 3
    3
      Marlin/Configuration_adv.h
  5. 8
    10
      Marlin/Marlin.h
  6. 369
    415
      Marlin/Marlin_main.cpp
  7. 21
    3
      Marlin/SanityCheck.h
  8. 1
    1
      Marlin/configurator/config/Configuration.h
  9. 3
    3
      Marlin/configurator/config/Configuration_adv.h
  10. 1
    1
      Marlin/dogm_lcd_implementation.h
  11. 1
    1
      Marlin/example_configurations/Felix/Configuration.h
  12. 1
    1
      Marlin/example_configurations/Felix/Configuration_DUAL.h
  13. 3
    3
      Marlin/example_configurations/Felix/Configuration_adv.h
  14. 1
    1
      Marlin/example_configurations/Hephestos/Configuration.h
  15. 3
    3
      Marlin/example_configurations/Hephestos/Configuration_adv.h
  16. 1
    1
      Marlin/example_configurations/K8200/Configuration.h
  17. 3
    3
      Marlin/example_configurations/K8200/Configuration_adv.h
  18. 1
    1
      Marlin/example_configurations/SCARA/Configuration.h
  19. 3
    3
      Marlin/example_configurations/SCARA/Configuration_adv.h
  20. 1
    1
      Marlin/example_configurations/WITBOX/Configuration.h
  21. 3
    3
      Marlin/example_configurations/WITBOX/Configuration_adv.h
  22. 5
    5
      Marlin/example_configurations/delta/generic/Configuration.h
  23. 3
    3
      Marlin/example_configurations/delta/generic/Configuration_adv.h
  24. 5
    5
      Marlin/example_configurations/delta/kossel_mini/Configuration.h
  25. 3
    3
      Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h
  26. 1
    1
      Marlin/example_configurations/makibox/Configuration.h
  27. 3
    3
      Marlin/example_configurations/makibox/Configuration_adv.h
  28. 1
    1
      Marlin/example_configurations/tvrrug/Round2/Configuration.h
  29. 3
    3
      Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h
  30. 1
    1
      Marlin/mesh_bed_leveling.h
  31. 5
    5
      Marlin/planner.cpp
  32. 58
    58
      Marlin/stepper.cpp
  33. 1
    1
      Marlin/temperature.h
  34. 8
    8
      Marlin/ultralcd.h

+ 75
- 18
Marlin/Conditionals.h View File

10
 
10
 
11
 #ifndef CONFIGURATION_LCD // Get the LCD defines which are needed first
11
 #ifndef CONFIGURATION_LCD // Get the LCD defines which are needed first
12
 
12
 
13
+  #define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0)
14
+
13
   #define CONFIGURATION_LCD
15
   #define CONFIGURATION_LCD
14
 
16
 
15
   #if defined(MAKRPANEL)
17
   #if defined(MAKRPANEL)
276
     #define PS_ON_AWAKE  HIGH
278
     #define PS_ON_AWAKE  HIGH
277
     #define PS_ON_ASLEEP LOW
279
     #define PS_ON_ASLEEP LOW
278
   #endif
280
   #endif
279
-  #define HAS_POWER_SWITCH (POWER_SUPPLY > 0 && defined(PS_ON_PIN) && PS_ON_PIN >= 0)
281
+  #define HAS_POWER_SWITCH (POWER_SUPPLY > 0 && PIN_EXISTS(PS_ON))
280
 
282
 
281
   /**
283
   /**
282
    * Temp Sensor defines
284
    * Temp Sensor defines
347
   #endif
349
   #endif
348
 
350
 
349
   /**
351
   /**
350
-   * Shorthand for pin tests, for temperature.cpp
352
+   * Shorthand for pin tests, used wherever needed
351
    */
353
    */
352
-  #define HAS_TEMP_0 (defined(TEMP_0_PIN) && TEMP_0_PIN >= 0 && TEMP_SENSOR_0 != 0 && TEMP_SENSOR_0 != -2)
353
-  #define HAS_TEMP_1 (defined(TEMP_1_PIN) && TEMP_1_PIN >= 0 && TEMP_SENSOR_1 != 0)
354
-  #define HAS_TEMP_2 (defined(TEMP_2_PIN) && TEMP_2_PIN >= 0 && TEMP_SENSOR_2 != 0)
355
-  #define HAS_TEMP_3 (defined(TEMP_3_PIN) && TEMP_3_PIN >= 0 && TEMP_SENSOR_3 != 0)
356
-  #define HAS_TEMP_BED (defined(TEMP_BED_PIN) && TEMP_BED_PIN >= 0 && TEMP_SENSOR_BED != 0)
357
-  #define HAS_FILAMENT_SENSOR (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0)
358
-  #define HAS_HEATER_0 (defined(HEATER_0_PIN) && HEATER_0_PIN >= 0)
359
-  #define HAS_HEATER_1 (defined(HEATER_1_PIN) && HEATER_1_PIN >= 0)
360
-  #define HAS_HEATER_2 (defined(HEATER_2_PIN) && HEATER_2_PIN >= 0)
361
-  #define HAS_HEATER_3 (defined(HEATER_3_PIN) && HEATER_3_PIN >= 0)
362
-  #define HAS_HEATER_BED (defined(HEATER_BED_PIN) && HEATER_BED_PIN >= 0)
363
-  #define HAS_AUTO_FAN_0 (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN >= 0)
364
-  #define HAS_AUTO_FAN_1 (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN >= 0)
365
-  #define HAS_AUTO_FAN_2 (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN >= 0)
366
-  #define HAS_AUTO_FAN_3 (defined(EXTRUDER_3_AUTO_FAN_PIN) && EXTRUDER_3_AUTO_FAN_PIN >= 0)
354
+  #define HAS_TEMP_0 (PIN_EXISTS(TEMP_0) && TEMP_SENSOR_0 != 0 && TEMP_SENSOR_0 != -2)
355
+  #define HAS_TEMP_1 (PIN_EXISTS(TEMP_1) && TEMP_SENSOR_1 != 0)
356
+  #define HAS_TEMP_2 (PIN_EXISTS(TEMP_2) && TEMP_SENSOR_2 != 0)
357
+  #define HAS_TEMP_3 (PIN_EXISTS(TEMP_3) && TEMP_SENSOR_3 != 0)
358
+  #define HAS_TEMP_BED (PIN_EXISTS(TEMP_BED) && TEMP_SENSOR_BED != 0)
359
+  #define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
360
+  #define HAS_HEATER_1 (PIN_EXISTS(HEATER_1))
361
+  #define HAS_HEATER_2 (PIN_EXISTS(HEATER_2))
362
+  #define HAS_HEATER_3 (PIN_EXISTS(HEATER_3))
363
+  #define HAS_HEATER_BED (PIN_EXISTS(HEATER_BED))
364
+  #define HAS_AUTO_FAN_0 (PIN_EXISTS(EXTRUDER_0_AUTO_FAN))
365
+  #define HAS_AUTO_FAN_1 (PIN_EXISTS(EXTRUDER_1_AUTO_FAN))
366
+  #define HAS_AUTO_FAN_2 (PIN_EXISTS(EXTRUDER_2_AUTO_FAN))
367
+  #define HAS_AUTO_FAN_3 (PIN_EXISTS(EXTRUDER_3_AUTO_FAN))
367
   #define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3)
368
   #define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3)
368
-  #define HAS_FAN (defined(FAN_PIN) && FAN_PIN >= 0)
369
+  #define HAS_FAN (PIN_EXISTS(FAN))
370
+  #define HAS_CONTROLLERFAN (PIN_EXISTS(CONTROLLERFAN))
371
+  #define HAS_SERVO_0 (PIN_EXISTS(SERVO0))
372
+  #define HAS_SERVO_1 (PIN_EXISTS(SERVO1))
373
+  #define HAS_SERVO_2 (PIN_EXISTS(SERVO2))
374
+  #define HAS_SERVO_3 (PIN_EXISTS(SERVO3))
375
+  #define HAS_FILAMENT_SENSOR (defined(FILAMENT_SENSOR) && PIN_EXISTS(FILWIDTH))
376
+  #define HAS_FILRUNOUT (PIN_EXISTS(FILRUNOUT))
377
+  #define HAS_HOME (PIN_EXISTS(HOME))
378
+  #define HAS_KILL (PIN_EXISTS(KILL))
379
+  #define HAS_SUICIDE (PIN_EXISTS(SUICIDE))
380
+  #define HAS_PHOTOGRAPH (PIN_EXISTS(PHOTOGRAPH))
381
+  #define HAS_X_MIN (PIN_EXISTS(X_MIN))
382
+  #define HAS_X_MAX (PIN_EXISTS(X_MAX))
383
+  #define HAS_Y_MIN (PIN_EXISTS(Y_MIN))
384
+  #define HAS_Y_MAX (PIN_EXISTS(Y_MAX))
385
+  #define HAS_Z_MIN (PIN_EXISTS(Z_MIN))
386
+  #define HAS_Z_MAX (PIN_EXISTS(Z_MAX))
387
+  #define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
388
+  #define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
389
+  #define HAS_SOLENOID_1 (PIN_EXISTS(SOL1))
390
+  #define HAS_SOLENOID_2 (PIN_EXISTS(SOL2))
391
+  #define HAS_SOLENOID_3 (PIN_EXISTS(SOL3))
392
+  #define HAS_MICROSTEPS (PIN_EXISTS(X_MS1))
393
+  #define HAS_MICROSTEPS_E0 (PIN_EXISTS(E0_MS1))
394
+  #define HAS_MICROSTEPS_E1 (PIN_EXISTS(E1_MS1))
395
+  #define HAS_MICROSTEPS_E2 (PIN_EXISTS(E2_MS1))
396
+  #define HAS_X_ENABLE (PIN_EXISTS(X_ENABLE))
397
+  #define HAS_X2_ENABLE (PIN_EXISTS(X2_ENABLE))
398
+  #define HAS_Y_ENABLE (PIN_EXISTS(Y_ENABLE))
399
+  #define HAS_Y2_ENABLE (PIN_EXISTS(Y2_ENABLE))
400
+  #define HAS_Z_ENABLE (PIN_EXISTS(Z_ENABLE))
401
+  #define HAS_Z2_ENABLE (PIN_EXISTS(Z2_ENABLE))
402
+  #define HAS_E0_ENABLE (PIN_EXISTS(E0_ENABLE))
403
+  #define HAS_E1_ENABLE (PIN_EXISTS(E1_ENABLE))
404
+  #define HAS_E2_ENABLE (PIN_EXISTS(E2_ENABLE))
405
+  #define HAS_E3_ENABLE (PIN_EXISTS(E3_ENABLE))
406
+  #define HAS_X_DIR (PIN_EXISTS(X_DIR))
407
+  #define HAS_X2_DIR (PIN_EXISTS(X2_DIR))
408
+  #define HAS_Y_DIR (PIN_EXISTS(Y_DIR))
409
+  #define HAS_Y2_DIR (PIN_EXISTS(Y2_DIR))
410
+  #define HAS_Z_DIR (PIN_EXISTS(Z_DIR))
411
+  #define HAS_Z2_DIR (PIN_EXISTS(Z2_DIR))
412
+  #define HAS_E0_DIR (PIN_EXISTS(E0_DIR))
413
+  #define HAS_E1_DIR (PIN_EXISTS(E1_DIR))
414
+  #define HAS_E2_DIR (PIN_EXISTS(E2_DIR))
415
+  #define HAS_E3_DIR (PIN_EXISTS(E3_DIR))
416
+  #define HAS_X_STEP (PIN_EXISTS(X_STEP))
417
+  #define HAS_X2_STEP (PIN_EXISTS(X2_STEP))
418
+  #define HAS_Y_STEP (PIN_EXISTS(Y_STEP))
419
+  #define HAS_Y2_STEP (PIN_EXISTS(Y2_STEP))
420
+  #define HAS_Z_STEP (PIN_EXISTS(Z_STEP))
421
+  #define HAS_Z2_STEP (PIN_EXISTS(Z2_STEP))
422
+  #define HAS_E0_STEP (PIN_EXISTS(E0_STEP))
423
+  #define HAS_E1_STEP (PIN_EXISTS(E1_STEP))
424
+  #define HAS_E2_STEP (PIN_EXISTS(E2_STEP))
425
+  #define HAS_E3_STEP (PIN_EXISTS(E3_STEP))
369
 
426
 
370
   /**
427
   /**
371
    * Helper Macros for heaters and extruder fan
428
    * Helper Macros for heaters and extruder fan

+ 2
- 2
Marlin/Configuration.h View File

387
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
387
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
388
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
388
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
389
 
389
 
390
-#if defined(MESH_BED_LEVELING)
390
+#ifdef MESH_BED_LEVELING
391
   #define MESH_MIN_X 10
391
   #define MESH_MIN_X 10
392
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
392
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
393
   #define MESH_MIN_Y 10
393
   #define MESH_MIN_Y 10
670
 // Data from: http://www.doc-diy.net/photo/rc-1_hacked/
670
 // Data from: http://www.doc-diy.net/photo/rc-1_hacked/
671
 // #define PHOTOGRAPH_PIN     23
671
 // #define PHOTOGRAPH_PIN     23
672
 
672
 
673
-// SF send wrong arc g-codes when using Arc Point as fillet procedure
673
+// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure
674
 //#define SF_ARC_FIX
674
 //#define SF_ARC_FIX
675
 
675
 
676
 // Support for the BariCUDA Paste Extruder.
676
 // Support for the BariCUDA Paste Extruder.

+ 2
- 2
Marlin/ConfigurationStore.cpp View File

78
 #include "ultralcd.h"
78
 #include "ultralcd.h"
79
 #include "ConfigurationStore.h"
79
 #include "ConfigurationStore.h"
80
 
80
 
81
-#if defined(MESH_BED_LEVELING)
81
+#ifdef MESH_BED_LEVELING
82
    #include "mesh_bed_leveling.h"
82
    #include "mesh_bed_leveling.h"
83
 #endif  // MESH_BED_LEVELING
83
 #endif  // MESH_BED_LEVELING
84
 
84
 
308
 
308
 
309
     uint8_t mesh_num_x = 0;
309
     uint8_t mesh_num_x = 0;
310
     uint8_t mesh_num_y = 0;
310
     uint8_t mesh_num_y = 0;
311
-    #if defined(MESH_BED_LEVELING)
311
+    #ifdef MESH_BED_LEVELING
312
       EEPROM_READ_VAR(i, mbl.active);
312
       EEPROM_READ_VAR(i, mbl.active);
313
       EEPROM_READ_VAR(i, mesh_num_x);
313
       EEPROM_READ_VAR(i, mesh_num_x);
314
       EEPROM_READ_VAR(i, mesh_num_y);
314
       EEPROM_READ_VAR(i, mesh_num_y);

+ 3
- 3
Marlin/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 2
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 2
181
 #define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {2, 2, 4}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 8
- 10
Marlin/Marlin.h View File

110
 
110
 
111
 void manage_inactivity(bool ignore_stepper_queue=false);
111
 void manage_inactivity(bool ignore_stepper_queue=false);
112
 
112
 
113
-#if defined(DUAL_X_CARRIAGE) && defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1 \
114
-    && defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
113
+#if defined(DUAL_X_CARRIAGE) && HAS_X_ENABLE && HAS_X2_ENABLE
115
   #define  enable_x() do { X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); } while (0)
114
   #define  enable_x() do { X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); } while (0)
116
   #define disable_x() do { X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0)
115
   #define disable_x() do { X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0)
117
-#elif defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
116
+#elif HAS_X_ENABLE
118
   #define  enable_x() X_ENABLE_WRITE( X_ENABLE_ON)
117
   #define  enable_x() X_ENABLE_WRITE( X_ENABLE_ON)
119
   #define disable_x() { X_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }
118
   #define disable_x() { X_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }
120
 #else
119
 #else
122
   #define disable_x() ;
121
   #define disable_x() ;
123
 #endif
122
 #endif
124
 
123
 
125
-#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
124
+#if HAS_Y_ENABLE
126
   #ifdef Y_DUAL_STEPPER_DRIVERS
125
   #ifdef Y_DUAL_STEPPER_DRIVERS
127
     #define  enable_y() { Y_ENABLE_WRITE( Y_ENABLE_ON); Y2_ENABLE_WRITE(Y_ENABLE_ON); }
126
     #define  enable_y() { Y_ENABLE_WRITE( Y_ENABLE_ON); Y2_ENABLE_WRITE(Y_ENABLE_ON); }
128
     #define disable_y() { Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
127
     #define disable_y() { Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
135
   #define disable_y() ;
134
   #define disable_y() ;
136
 #endif
135
 #endif
137
 
136
 
138
-#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
137
+#if HAS_Z_ENABLE
139
   #ifdef Z_DUAL_STEPPER_DRIVERS
138
   #ifdef Z_DUAL_STEPPER_DRIVERS
140
     #define  enable_z() { Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); }
139
     #define  enable_z() { Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); }
141
     #define disable_z() { Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
140
     #define disable_z() { Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
148
   #define disable_z() ;
147
   #define disable_z() ;
149
 #endif
148
 #endif
150
 
149
 
151
-#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
150
+#if HAS_E0_ENABLE
152
   #define enable_e0() E0_ENABLE_WRITE(E_ENABLE_ON)
151
   #define enable_e0() E0_ENABLE_WRITE(E_ENABLE_ON)
153
   #define disable_e0() E0_ENABLE_WRITE(!E_ENABLE_ON)
152
   #define disable_e0() E0_ENABLE_WRITE(!E_ENABLE_ON)
154
 #else
153
 #else
156
   #define disable_e0() /* nothing */
155
   #define disable_e0() /* nothing */
157
 #endif
156
 #endif
158
 
157
 
159
-#if (EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
158
+#if (EXTRUDERS > 1) && HAS_E1_ENABLE
160
   #define enable_e1() E1_ENABLE_WRITE(E_ENABLE_ON)
159
   #define enable_e1() E1_ENABLE_WRITE(E_ENABLE_ON)
161
   #define disable_e1() E1_ENABLE_WRITE(!E_ENABLE_ON)
160
   #define disable_e1() E1_ENABLE_WRITE(!E_ENABLE_ON)
162
 #else
161
 #else
164
   #define disable_e1() /* nothing */
163
   #define disable_e1() /* nothing */
165
 #endif
164
 #endif
166
 
165
 
167
-#if (EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
166
+#if (EXTRUDERS > 2) && HAS_E2_ENABLE
168
   #define enable_e2() E2_ENABLE_WRITE(E_ENABLE_ON)
167
   #define enable_e2() E2_ENABLE_WRITE(E_ENABLE_ON)
169
   #define disable_e2() E2_ENABLE_WRITE(!E_ENABLE_ON)
168
   #define disable_e2() E2_ENABLE_WRITE(!E_ENABLE_ON)
170
 #else
169
 #else
172
   #define disable_e2() /* nothing */
171
   #define disable_e2() /* nothing */
173
 #endif
172
 #endif
174
 
173
 
175
-#if (EXTRUDERS > 3) && defined(E3_ENABLE_PIN) && (E3_ENABLE_PIN > -1)
174
+#if (EXTRUDERS > 3) && HAS_E3_ENABLE
176
   #define enable_e3() E3_ENABLE_WRITE(E_ENABLE_ON)
175
   #define enable_e3() E3_ENABLE_WRITE(E_ENABLE_ON)
177
   #define disable_e3() E3_ENABLE_WRITE(!E_ENABLE_ON)
176
   #define disable_e3() E3_ENABLE_WRITE(!E_ENABLE_ON)
178
 #else
177
 #else
194
     void adjust_delta(float cartesian[3]);
193
     void adjust_delta(float cartesian[3]);
195
   #endif
194
   #endif
196
   extern float delta[3];
195
   extern float delta[3];
197
-  void prepare_move_raw();
198
 #endif
196
 #endif
199
 #ifdef SCARA
197
 #ifdef SCARA
200
   void calculate_delta(float cartesian[3]);
198
   void calculate_delta(float cartesian[3]);

+ 369
- 415
Marlin/Marlin_main.cpp
File diff suppressed because it is too large
View File


+ 21
- 3
Marlin/SanityCheck.h View File

56
   #if EXTRUDERS > 1
56
   #if EXTRUDERS > 1
57
 
57
 
58
     #if EXTRUDERS > 4
58
     #if EXTRUDERS > 4
59
-      #error The maximum number of EXTRUDERS is 4.
59
+      #error The maximum number of EXTRUDERS in Marlin is 4.
60
     #endif
60
     #endif
61
 
61
 
62
     #ifdef TEMP_SENSOR_1_AS_REDUNDANT
62
     #ifdef TEMP_SENSOR_1_AS_REDUNDANT
78
   #endif // EXTRUDERS > 1
78
   #endif // EXTRUDERS > 1
79
 
79
 
80
   /**
80
   /**
81
+   * Limited number of servos
82
+   */
83
+  #if NUM_SERVOS > 4
84
+    #error The maximum number of SERVOS in Marlin is 4.
85
+  #endif
86
+
87
+  /**
81
    * Required LCD language
88
    * Required LCD language
82
    */
89
    */
83
   #if !defined(DOGLCD) && defined(ULTRA_LCD) && !defined(DISPLAY_CHARSET_HD44780_JAPAN) && !defined(DISPLAY_CHARSET_HD44780_WESTERN)
90
   #if !defined(DOGLCD) && defined(ULTRA_LCD) && !defined(DISPLAY_CHARSET_HD44780_JAPAN) && !defined(DISPLAY_CHARSET_HD44780_WESTERN)
209
    */
216
    */
210
   #ifdef DUAL_X_CARRIAGE
217
   #ifdef DUAL_X_CARRIAGE
211
     #if EXTRUDERS == 1 || defined(COREXY) \
218
     #if EXTRUDERS == 1 || defined(COREXY) \
212
-        || !defined(X2_ENABLE_PIN) || !defined(X2_STEP_PIN) || !defined(X2_DIR_PIN) \
219
+        || !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR \
213
         || !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \
220
         || !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \
214
-        || !defined(X_MAX_PIN) || X_MAX_PIN < 0
221
+        || !HAS_X_MAX
215
       #error Missing or invalid definitions for DUAL_X_CARRIAGE mode.
222
       #error Missing or invalid definitions for DUAL_X_CARRIAGE mode.
216
     #endif
223
     #endif
217
     #if X_HOME_DIR != -1 || X2_HOME_DIR != 1
224
     #if X_HOME_DIR != -1 || X2_HOME_DIR != 1
234
     #endif
241
     #endif
235
   #endif
242
   #endif
236
 
243
 
244
+  #if HAS_FAN && CONTROLLERFAN_PIN == FAN_PIN
245
+    #error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN
246
+  #endif
247
+
237
   /**
248
   /**
238
    * Test required HEATER defines
249
    * Test required HEATER defines
239
    */
250
    */
254
     #error HEATER_0_PIN not defined for this board
265
     #error HEATER_0_PIN not defined for this board
255
   #endif
266
   #endif
256
 
267
 
268
+  /**
269
+   * Warnings for old configurations
270
+   */
271
+  #ifdef X_HOME_RETRACT_MM
272
+    #error [XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM
273
+  #endif
274
+
257
 #endif //SANITYCHECK_H
275
 #endif //SANITYCHECK_H

+ 1
- 1
Marlin/configurator/config/Configuration.h View File

412
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
412
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
413
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
413
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
414
 
414
 
415
-#if defined(MESH_BED_LEVELING)
415
+#ifdef MESH_BED_LEVELING
416
   #define MESH_MIN_X 10
416
   #define MESH_MIN_X 10
417
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
417
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
418
   #define MESH_MIN_Y 10
418
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/configurator/config/Configuration_adv.h View File

189
 // @section homing
189
 // @section homing
190
 
190
 
191
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
191
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
192
-#define X_HOME_RETRACT_MM 5
193
-#define Y_HOME_RETRACT_MM 5
194
-#define Z_HOME_RETRACT_MM 2
192
+#define X_HOME_BUMP_MM 5
193
+#define Y_HOME_BUMP_MM 5
194
+#define Z_HOME_BUMP_MM 2
195
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
195
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
196
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
196
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
197
 
197
 

+ 1
- 1
Marlin/dogm_lcd_implementation.h View File

300
   // Fan
300
   // Fan
301
   lcd_setFont(FONT_STATUSMENU);
301
   lcd_setFont(FONT_STATUSMENU);
302
   u8g.setPrintPos(104,27);
302
   u8g.setPrintPos(104,27);
303
-  #if defined(FAN_PIN) && FAN_PIN > -1
303
+  #if HAS_FAN
304
     int per = ((fanSpeed + 1) * 100) / 256;
304
     int per = ((fanSpeed + 1) * 100) / 256;
305
     if (per) {
305
     if (per) {
306
 
306
 

+ 1
- 1
Marlin/example_configurations/Felix/Configuration.h View File

364
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
364
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
365
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
365
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
366
 
366
 
367
-#if defined(MESH_BED_LEVELING)
367
+#ifdef MESH_BED_LEVELING
368
   #define MESH_MIN_X 10
368
   #define MESH_MIN_X 10
369
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
369
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
370
   #define MESH_MIN_Y 10
370
   #define MESH_MIN_Y 10

+ 1
- 1
Marlin/example_configurations/Felix/Configuration_DUAL.h View File

364
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
364
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
365
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
365
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
366
 
366
 
367
-#if defined(MESH_BED_LEVELING)
367
+#ifdef MESH_BED_LEVELING
368
   #define MESH_MIN_X 10
368
   #define MESH_MIN_X 10
369
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
369
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
370
   #define MESH_MIN_Y 10
370
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/example_configurations/Felix/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 3
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 3
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 1
- 1
Marlin/example_configurations/Hephestos/Configuration.h View File

387
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
387
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
388
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
388
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
389
 
389
 
390
-#if defined(MESH_BED_LEVELING)
390
+#ifdef MESH_BED_LEVELING
391
   #define MESH_MIN_X 10
391
   #define MESH_MIN_X 10
392
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
392
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
393
   #define MESH_MIN_Y 10
393
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/example_configurations/Hephestos/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 2
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 2
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 1
- 1
Marlin/example_configurations/K8200/Configuration.h View File

392
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
392
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
393
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
393
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
394
 
394
 
395
-#if defined(MESH_BED_LEVELING)
395
+#ifdef MESH_BED_LEVELING
396
   #define MESH_MIN_X 10
396
   #define MESH_MIN_X 10
397
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
397
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
398
   #define MESH_MIN_Y 10
398
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/example_configurations/K8200/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 3
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 3
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 1
- 1
Marlin/example_configurations/SCARA/Configuration.h View File

416
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
416
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
417
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
417
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
418
 
418
 
419
-#if defined(MESH_BED_LEVELING)
419
+#ifdef MESH_BED_LEVELING
420
   #define MESH_MIN_X 10
420
   #define MESH_MIN_X 10
421
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
421
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
422
   #define MESH_MIN_Y 10
422
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/example_configurations/SCARA/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 3
179
-#define Y_HOME_RETRACT_MM 3
180
-#define Z_HOME_RETRACT_MM 3
178
+#define X_HOME_BUMP_MM 3
179
+#define Y_HOME_BUMP_MM 3
180
+#define Z_HOME_BUMP_MM 3
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 1
- 1
Marlin/example_configurations/WITBOX/Configuration.h View File

386
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
386
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
387
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
387
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
388
 
388
 
389
-#if defined(MESH_BED_LEVELING)
389
+#ifdef MESH_BED_LEVELING
390
   #define MESH_MIN_X 10
390
   #define MESH_MIN_X 10
391
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
391
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
392
   #define MESH_MIN_Y 10
392
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/example_configurations/WITBOX/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 2
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 2
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 5
- 5
Marlin/example_configurations/delta/generic/Configuration.h View File

414
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
414
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
415
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
415
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
416
 
416
 
417
-#if defined(MESH_BED_LEVELING)
417
+#ifdef MESH_BED_LEVELING
418
   #define MESH_MIN_X 10
418
   #define MESH_MIN_X 10
419
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
419
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
420
   #define MESH_MIN_Y 10
420
   #define MESH_MIN_Y 10
507
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Y DELTA_PRINTABLE_RADIUS
507
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Y DELTA_PRINTABLE_RADIUS
508
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Z 100
508
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Z 100
509
     
509
     
510
-    #define Z_PROBE_ALLEN_KEY_RETRACT_X     -64
511
-    #define Z_PROBE_ALLEN_KEY_RETRACT_Y     56
512
-    #define Z_PROBE_ALLEN_KEY_RETRACT_Z     23
513
-    #define Z_PROBE_ALLEN_KEY_RETRACT_DEPTH 20
510
+    #define Z_PROBE_ALLEN_KEY_STOW_X     -64
511
+    #define Z_PROBE_ALLEN_KEY_STOW_Y     56
512
+    #define Z_PROBE_ALLEN_KEY_STOW_Z     23
513
+    #define Z_PROBE_ALLEN_KEY_STOW_DEPTH 20
514
   #endif
514
   #endif
515
   
515
   
516
   //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk
516
   //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk

+ 3
- 3
Marlin/example_configurations/delta/generic/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 5 // deltas need the same for all three axis
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 5
- 5
Marlin/example_configurations/delta/kossel_mini/Configuration.h View File

414
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
414
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
415
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
415
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
416
 
416
 
417
-#if defined(MESH_BED_LEVELING)
417
+#ifdef MESH_BED_LEVELING
418
   #define MESH_MIN_X 10
418
   #define MESH_MIN_X 10
419
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
419
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
420
   #define MESH_MIN_Y 10
420
   #define MESH_MIN_Y 10
511
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Y DELTA_PRINTABLE_RADIUS
511
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Y DELTA_PRINTABLE_RADIUS
512
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Z 100
512
     #define Z_PROBE_ALLEN_KEY_DEPLOY_Z 100
513
     
513
     
514
-    #define Z_PROBE_ALLEN_KEY_RETRACT_X     -64
515
-    #define Z_PROBE_ALLEN_KEY_RETRACT_Y     56
516
-    #define Z_PROBE_ALLEN_KEY_RETRACT_Z     23
517
-    #define Z_PROBE_ALLEN_KEY_RETRACT_DEPTH 20
514
+    #define Z_PROBE_ALLEN_KEY_STOW_X     -64
515
+    #define Z_PROBE_ALLEN_KEY_STOW_Y     56
516
+    #define Z_PROBE_ALLEN_KEY_STOW_Z     23
517
+    #define Z_PROBE_ALLEN_KEY_STOW_DEPTH 20
518
   #endif
518
   #endif
519
   
519
   
520
   //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk
520
   //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk

+ 3
- 3
Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 5 // deltas need the same for all three axis
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 1
- 1
Marlin/example_configurations/makibox/Configuration.h View File

384
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
384
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
385
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
385
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
386
 
386
 
387
-#if defined(MESH_BED_LEVELING)
387
+#ifdef MESH_BED_LEVELING
388
   #define MESH_MIN_X 10
388
   #define MESH_MIN_X 10
389
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
389
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
390
   #define MESH_MIN_Y 10
390
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/example_configurations/makibox/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 2
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 2
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 1
- 1
Marlin/example_configurations/tvrrug/Round2/Configuration.h View File

386
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
386
 // #define MANUAL_BED_LEVELING  // Add display menu option for bed leveling
387
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
387
 // #define MESH_BED_LEVELING    // Enable mesh bed leveling
388
 
388
 
389
-#if defined(MESH_BED_LEVELING)
389
+#ifdef MESH_BED_LEVELING
390
   #define MESH_MIN_X 10
390
   #define MESH_MIN_X 10
391
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
391
   #define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
392
   #define MESH_MIN_Y 10
392
   #define MESH_MIN_Y 10

+ 3
- 3
Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h View File

175
 #endif //DUAL_X_CARRIAGE
175
 #endif //DUAL_X_CARRIAGE
176
 
176
 
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
177
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
178
-#define X_HOME_RETRACT_MM 5
179
-#define Y_HOME_RETRACT_MM 5
180
-#define Z_HOME_RETRACT_MM 1
178
+#define X_HOME_BUMP_MM 5
179
+#define Y_HOME_BUMP_MM 5
180
+#define Z_HOME_BUMP_MM 1
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
181
 #define HOMING_BUMP_DIVISOR {10, 10, 20}  // Re-Bump Speed Divisor (Divides the Homing Feedrate)
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
182
 //#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
183
 
183
 

+ 1
- 1
Marlin/mesh_bed_leveling.h View File

1
 #include "Marlin.h"
1
 #include "Marlin.h"
2
 
2
 
3
-#if defined(MESH_BED_LEVELING)
3
+#ifdef MESH_BED_LEVELING
4
 
4
 
5
   #define MESH_X_DIST ((MESH_MAX_X - MESH_MIN_X)/(MESH_NUM_X_POINTS - 1))
5
   #define MESH_X_DIST ((MESH_MAX_X - MESH_MIN_X)/(MESH_NUM_X_POINTS - 1))
6
   #define MESH_Y_DIST ((MESH_MAX_Y - MESH_MIN_Y)/(MESH_NUM_Y_POINTS - 1))
6
   #define MESH_Y_DIST ((MESH_MAX_Y - MESH_MIN_Y)/(MESH_NUM_Y_POINTS - 1))

+ 5
- 5
Marlin/planner.cpp View File

58
 #include "ultralcd.h"
58
 #include "ultralcd.h"
59
 #include "language.h"
59
 #include "language.h"
60
 
60
 
61
-#if defined(MESH_BED_LEVELING)
61
+#ifdef MESH_BED_LEVELING
62
   #include "mesh_bed_leveling.h"
62
   #include "mesh_bed_leveling.h"
63
 #endif  // MESH_BED_LEVELING
63
 #endif  // MESH_BED_LEVELING
64
 
64
 
427
     disable_e3();
427
     disable_e3();
428
   }
428
   }
429
 
429
 
430
-  #if defined(FAN_PIN) && FAN_PIN > -1 // HAS_FAN
430
+  #if HAS_FAN
431
     #ifdef FAN_KICKSTART_TIME
431
     #ifdef FAN_KICKSTART_TIME
432
       static unsigned long fan_kick_end;
432
       static unsigned long fan_kick_end;
433
       if (tail_fan_speed) {
433
       if (tail_fan_speed) {
447
     #else
447
     #else
448
       analogWrite(FAN_PIN, tail_fan_speed);
448
       analogWrite(FAN_PIN, tail_fan_speed);
449
     #endif //!FAN_SOFT_PWM
449
     #endif //!FAN_SOFT_PWM
450
-  #endif //FAN_PIN > -1
450
+  #endif // HAS_FAN
451
 
451
 
452
   #ifdef AUTOTEMP
452
   #ifdef AUTOTEMP
453
     getHighESpeed();
453
     getHighESpeed();
454
   #endif
454
   #endif
455
 
455
 
456
   #ifdef BARICUDA
456
   #ifdef BARICUDA
457
-    #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1 // HAS_HEATER_1
457
+    #if HAS_HEATER_1
458
       analogWrite(HEATER_1_PIN,tail_valve_pressure);
458
       analogWrite(HEATER_1_PIN,tail_valve_pressure);
459
     #endif
459
     #endif
460
-    #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1 // HAS_HEATER_2
460
+    #if HAS_HEATER_2
461
       analogWrite(HEATER_2_PIN,tail_e_to_p_pressure);
461
       analogWrite(HEATER_2_PIN,tail_e_to_p_pressure);
462
     #endif
462
     #endif
463
   #endif
463
   #endif

+ 58
- 58
Marlin/stepper.cpp View File

85
   int motor_current_setting[3] = DEFAULT_PWM_MOTOR_CURRENT;
85
   int motor_current_setting[3] = DEFAULT_PWM_MOTOR_CURRENT;
86
 #endif
86
 #endif
87
 
87
 
88
-#if defined(X_MIN_PIN) && X_MIN_PIN >= 0
88
+#if HAS_X_MIN
89
   static bool old_x_min_endstop = false;
89
   static bool old_x_min_endstop = false;
90
 #endif
90
 #endif
91
-#if defined(X_MAX_PIN) && X_MAX_PIN >= 0
91
+#if HAS_X_MAX
92
   static bool old_x_max_endstop = false;
92
   static bool old_x_max_endstop = false;
93
 #endif
93
 #endif
94
-#if defined(Y_MIN_PIN) && Y_MIN_PIN >= 0
94
+#if HAS_Y_MIN
95
   static bool old_y_min_endstop = false;
95
   static bool old_y_min_endstop = false;
96
 #endif
96
 #endif
97
-#if defined(Y_MAX_PIN) && Y_MAX_PIN >= 0
97
+#if HAS_Y_MAX
98
   static bool old_y_max_endstop = false;
98
   static bool old_y_max_endstop = false;
99
 #endif
99
 #endif
100
-#if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0
100
+#if HAS_Z_MIN
101
   static bool old_z_min_endstop = false;
101
   static bool old_z_min_endstop = false;
102
 #endif
102
 #endif
103
-#if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0
103
+#if HAS_Z_MAX
104
   static bool old_z_max_endstop = false;
104
   static bool old_z_max_endstop = false;
105
 #endif
105
 #endif
106
 #ifdef Z_DUAL_ENDSTOPS
106
 #ifdef Z_DUAL_ENDSTOPS
107
-  #if defined(Z2_MIN_PIN) && Z2_MIN_PIN >= 0
107
+  #if HAS_Z2_MIN
108
     static bool old_z2_min_endstop = false;
108
     static bool old_z2_min_endstop = false;
109
   #endif
109
   #endif
110
-  #if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0
110
+  #if HAS_Z2_MAX
111
     static bool old_z2_max_endstop = false;
111
     static bool old_z2_max_endstop = false;
112
   #endif
112
   #endif
113
 #endif
113
 #endif
472
               if ((current_block->active_extruder == 0 && X_HOME_DIR == -1) || (current_block->active_extruder != 0 && X2_HOME_DIR == -1))
472
               if ((current_block->active_extruder == 0 && X_HOME_DIR == -1) || (current_block->active_extruder != 0 && X2_HOME_DIR == -1))
473
             #endif          
473
             #endif          
474
               {
474
               {
475
-                #if defined(X_MIN_PIN) && X_MIN_PIN >= 0
475
+                #if HAS_X_MIN
476
                   UPDATE_ENDSTOP(x, X, min, MIN);
476
                   UPDATE_ENDSTOP(x, X, min, MIN);
477
                 #endif
477
                 #endif
478
               }
478
               }
483
               if ((current_block->active_extruder == 0 && X_HOME_DIR == 1) || (current_block->active_extruder != 0 && X2_HOME_DIR == 1))
483
               if ((current_block->active_extruder == 0 && X_HOME_DIR == 1) || (current_block->active_extruder != 0 && X2_HOME_DIR == 1))
484
             #endif
484
             #endif
485
               {
485
               {
486
-                #if defined(X_MAX_PIN) && X_MAX_PIN >= 0
486
+                #if HAS_X_MAX
487
                   UPDATE_ENDSTOP(x, X, max, MAX);
487
                   UPDATE_ENDSTOP(x, X, max, MAX);
488
                 #endif
488
                 #endif
489
               }
489
               }
498
           if (TEST(out_bits, Y_AXIS))   // -direction
498
           if (TEST(out_bits, Y_AXIS))   // -direction
499
       #endif
499
       #endif
500
           { // -direction
500
           { // -direction
501
-            #if defined(Y_MIN_PIN) && Y_MIN_PIN >= 0
501
+            #if HAS_Y_MIN
502
               UPDATE_ENDSTOP(y, Y, min, MIN);
502
               UPDATE_ENDSTOP(y, Y, min, MIN);
503
             #endif
503
             #endif
504
           }
504
           }
505
           else { // +direction
505
           else { // +direction
506
-            #if defined(Y_MAX_PIN) && Y_MAX_PIN >= 0
506
+            #if HAS_Y_MAX
507
               UPDATE_ENDSTOP(y, Y, max, MAX);
507
               UPDATE_ENDSTOP(y, Y, max, MAX);
508
             #endif
508
             #endif
509
           }
509
           }
519
 
519
 
520
       if (check_endstops) {
520
       if (check_endstops) {
521
 
521
 
522
-        #if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0
522
+        #if HAS_Z_MIN
523
 
523
 
524
           #ifdef Z_DUAL_ENDSTOPS
524
           #ifdef Z_DUAL_ENDSTOPS
525
 
525
 
526
             bool z_min_endstop = READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING,
526
             bool z_min_endstop = READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING,
527
                 z2_min_endstop =
527
                 z2_min_endstop =
528
-                  #if defined(Z2_MIN_PIN) && Z2_MIN_PIN >= 0
528
+                  #if HAS_Z2_MIN
529
                     READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING
529
                     READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING
530
                   #else
530
                   #else
531
                     z_min_endstop
531
                     z_min_endstop
561
 
561
 
562
       if (check_endstops) {
562
       if (check_endstops) {
563
 
563
 
564
-        #if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0
564
+        #if HAS_Z_MAX
565
 
565
 
566
           #ifdef Z_DUAL_ENDSTOPS
566
           #ifdef Z_DUAL_ENDSTOPS
567
 
567
 
568
             bool z_max_endstop = READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING,
568
             bool z_max_endstop = READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING,
569
                 z2_max_endstop =
569
                 z2_max_endstop =
570
-                  #if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0
570
+                  #if HAS_Z2_MAX
571
                     READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING
571
                     READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING
572
                   #else
572
                   #else
573
                     z_max_endstop
573
                     z_max_endstop
835
   #endif
835
   #endif
836
   
836
   
837
   // Initialize Dir Pins
837
   // Initialize Dir Pins
838
-  #if defined(X_DIR_PIN) && X_DIR_PIN >= 0
838
+  #if HAS_X_DIR
839
     X_DIR_INIT;
839
     X_DIR_INIT;
840
   #endif
840
   #endif
841
-  #if defined(X2_DIR_PIN) && X2_DIR_PIN >= 0
841
+  #if HAS_X2_DIR
842
     X2_DIR_INIT;
842
     X2_DIR_INIT;
843
   #endif
843
   #endif
844
-  #if defined(Y_DIR_PIN) && Y_DIR_PIN >= 0
844
+  #if HAS_Y_DIR
845
     Y_DIR_INIT;
845
     Y_DIR_INIT;
846
-    #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_DIR_PIN) && Y2_DIR_PIN >= 0
846
+    #if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_DIR
847
       Y2_DIR_INIT;
847
       Y2_DIR_INIT;
848
     #endif
848
     #endif
849
   #endif
849
   #endif
850
-  #if defined(Z_DIR_PIN) && Z_DIR_PIN >= 0
850
+  #if HAS_Z_DIR
851
     Z_DIR_INIT;
851
     Z_DIR_INIT;
852
-    #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_DIR_PIN) && Z2_DIR_PIN >= 0
852
+    #if defined(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_DIR
853
       Z2_DIR_INIT;
853
       Z2_DIR_INIT;
854
     #endif
854
     #endif
855
   #endif
855
   #endif
856
-  #if defined(E0_DIR_PIN) && E0_DIR_PIN >= 0
856
+  #if HAS_E0_DIR
857
     E0_DIR_INIT;
857
     E0_DIR_INIT;
858
   #endif
858
   #endif
859
-  #if defined(E1_DIR_PIN) && E1_DIR_PIN >= 0
859
+  #if HAS_E1_DIR
860
     E1_DIR_INIT;
860
     E1_DIR_INIT;
861
   #endif
861
   #endif
862
-  #if defined(E2_DIR_PIN) && E2_DIR_PIN >= 0
862
+  #if HAS_E2_DIR
863
     E2_DIR_INIT;
863
     E2_DIR_INIT;
864
   #endif
864
   #endif
865
-  #if defined(E3_DIR_PIN) && E3_DIR_PIN >= 0
865
+  #if HAS_E3_DIR
866
     E3_DIR_INIT;
866
     E3_DIR_INIT;
867
   #endif
867
   #endif
868
 
868
 
869
   //Initialize Enable Pins - steppers default to disabled.
869
   //Initialize Enable Pins - steppers default to disabled.
870
 
870
 
871
-  #if defined(X_ENABLE_PIN) && X_ENABLE_PIN >= 0
871
+  #if HAS_X_ENABLE
872
     X_ENABLE_INIT;
872
     X_ENABLE_INIT;
873
     if (!X_ENABLE_ON) X_ENABLE_WRITE(HIGH);
873
     if (!X_ENABLE_ON) X_ENABLE_WRITE(HIGH);
874
   #endif
874
   #endif
875
-  #if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN >= 0
875
+  #if HAS_X2_ENABLE
876
     X2_ENABLE_INIT;
876
     X2_ENABLE_INIT;
877
     if (!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH);
877
     if (!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH);
878
   #endif
878
   #endif
879
-  #if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN >= 0
879
+  #if HAS_Y_ENABLE
880
     Y_ENABLE_INIT;
880
     Y_ENABLE_INIT;
881
     if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH);
881
     if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH);
882
 	
882
 	
883
-	#if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_ENABLE_PIN) && Y2_ENABLE_PIN >= 0
883
+	#if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_ENABLE
884
 	  Y2_ENABLE_INIT;
884
 	  Y2_ENABLE_INIT;
885
 	  if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH);
885
 	  if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH);
886
 	#endif
886
 	#endif
887
   #endif
887
   #endif
888
-  #if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN >= 0
888
+  #if HAS_Z_ENABLE
889
     Z_ENABLE_INIT;
889
     Z_ENABLE_INIT;
890
     if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
890
     if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
891
 
891
 
892
-    #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_ENABLE_PIN) && Z2_ENABLE_PIN >= 0
892
+    #if defined(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_ENABLE
893
       Z2_ENABLE_INIT;
893
       Z2_ENABLE_INIT;
894
       if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
894
       if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
895
     #endif
895
     #endif
896
   #endif
896
   #endif
897
-  #if defined(E0_ENABLE_PIN) && E0_ENABLE_PIN >= 0
897
+  #if HAS_E0_ENABLE
898
     E0_ENABLE_INIT;
898
     E0_ENABLE_INIT;
899
     if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
899
     if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
900
   #endif
900
   #endif
901
-  #if defined(E1_ENABLE_PIN) && E1_ENABLE_PIN >= 0
901
+  #if HAS_E1_ENABLE
902
     E1_ENABLE_INIT;
902
     E1_ENABLE_INIT;
903
     if (!E_ENABLE_ON) E1_ENABLE_WRITE(HIGH);
903
     if (!E_ENABLE_ON) E1_ENABLE_WRITE(HIGH);
904
   #endif
904
   #endif
905
-  #if defined(E2_ENABLE_PIN) && E2_ENABLE_PIN >= 0
905
+  #if HAS_E2_ENABLE
906
     E2_ENABLE_INIT;
906
     E2_ENABLE_INIT;
907
     if (!E_ENABLE_ON) E2_ENABLE_WRITE(HIGH);
907
     if (!E_ENABLE_ON) E2_ENABLE_WRITE(HIGH);
908
   #endif
908
   #endif
909
-  #if defined(E3_ENABLE_PIN) && E3_ENABLE_PIN >= 0
909
+  #if HAS_E3_ENABLE
910
     E3_ENABLE_INIT;
910
     E3_ENABLE_INIT;
911
     if (!E_ENABLE_ON) E3_ENABLE_WRITE(HIGH);
911
     if (!E_ENABLE_ON) E3_ENABLE_WRITE(HIGH);
912
   #endif
912
   #endif
913
 
913
 
914
   //endstops and pullups
914
   //endstops and pullups
915
 
915
 
916
-  #if defined(X_MIN_PIN) && X_MIN_PIN >= 0
916
+  #if HAS_X_MIN
917
     SET_INPUT(X_MIN_PIN);
917
     SET_INPUT(X_MIN_PIN);
918
     #ifdef ENDSTOPPULLUP_XMIN
918
     #ifdef ENDSTOPPULLUP_XMIN
919
       WRITE(X_MIN_PIN,HIGH);
919
       WRITE(X_MIN_PIN,HIGH);
920
     #endif
920
     #endif
921
   #endif
921
   #endif
922
 
922
 
923
-  #if defined(Y_MIN_PIN) && Y_MIN_PIN >= 0
923
+  #if HAS_Y_MIN
924
     SET_INPUT(Y_MIN_PIN);
924
     SET_INPUT(Y_MIN_PIN);
925
     #ifdef ENDSTOPPULLUP_YMIN
925
     #ifdef ENDSTOPPULLUP_YMIN
926
       WRITE(Y_MIN_PIN,HIGH);
926
       WRITE(Y_MIN_PIN,HIGH);
927
     #endif
927
     #endif
928
   #endif
928
   #endif
929
 
929
 
930
-  #if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0
930
+  #if HAS_Z_MIN
931
     SET_INPUT(Z_MIN_PIN);
931
     SET_INPUT(Z_MIN_PIN);
932
     #ifdef ENDSTOPPULLUP_ZMIN
932
     #ifdef ENDSTOPPULLUP_ZMIN
933
       WRITE(Z_MIN_PIN,HIGH);
933
       WRITE(Z_MIN_PIN,HIGH);
934
     #endif
934
     #endif
935
   #endif
935
   #endif
936
 
936
 
937
-  #if defined(X_MAX_PIN) && X_MAX_PIN >= 0
937
+  #if HAS_X_MAX
938
     SET_INPUT(X_MAX_PIN);
938
     SET_INPUT(X_MAX_PIN);
939
     #ifdef ENDSTOPPULLUP_XMAX
939
     #ifdef ENDSTOPPULLUP_XMAX
940
       WRITE(X_MAX_PIN,HIGH);
940
       WRITE(X_MAX_PIN,HIGH);
941
     #endif
941
     #endif
942
   #endif
942
   #endif
943
 
943
 
944
-  #if defined(Y_MAX_PIN) && Y_MAX_PIN >= 0
944
+  #if HAS_Y_MAX
945
     SET_INPUT(Y_MAX_PIN);
945
     SET_INPUT(Y_MAX_PIN);
946
     #ifdef ENDSTOPPULLUP_YMAX
946
     #ifdef ENDSTOPPULLUP_YMAX
947
       WRITE(Y_MAX_PIN,HIGH);
947
       WRITE(Y_MAX_PIN,HIGH);
948
     #endif
948
     #endif
949
   #endif
949
   #endif
950
 
950
 
951
-  #if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0
951
+  #if HAS_Z_MAX
952
     SET_INPUT(Z_MAX_PIN);
952
     SET_INPUT(Z_MAX_PIN);
953
     #ifdef ENDSTOPPULLUP_ZMAX
953
     #ifdef ENDSTOPPULLUP_ZMAX
954
       WRITE(Z_MAX_PIN,HIGH);
954
       WRITE(Z_MAX_PIN,HIGH);
955
     #endif
955
     #endif
956
   #endif
956
   #endif
957
 
957
 
958
-  #if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0
958
+  #if HAS_Z2_MAX
959
     SET_INPUT(Z2_MAX_PIN);
959
     SET_INPUT(Z2_MAX_PIN);
960
     #ifdef ENDSTOPPULLUP_ZMAX
960
     #ifdef ENDSTOPPULLUP_ZMAX
961
       WRITE(Z2_MAX_PIN,HIGH);
961
       WRITE(Z2_MAX_PIN,HIGH);
970
   #define E_AXIS_INIT(NUM) AXIS_INIT(e## NUM, E## NUM, E)
970
   #define E_AXIS_INIT(NUM) AXIS_INIT(e## NUM, E## NUM, E)
971
 
971
 
972
   // Initialize Step Pins
972
   // Initialize Step Pins
973
-  #if defined(X_STEP_PIN) && X_STEP_PIN >= 0
973
+  #if HAS_X_STEP
974
     AXIS_INIT(x, X, X);
974
     AXIS_INIT(x, X, X);
975
   #endif
975
   #endif
976
-  #if defined(X2_STEP_PIN) && X2_STEP_PIN >= 0
976
+  #if HAS_X2_STEP
977
     AXIS_INIT(x, X2, X);
977
     AXIS_INIT(x, X2, X);
978
   #endif
978
   #endif
979
-  #if defined(Y_STEP_PIN) && Y_STEP_PIN >= 0
980
-    #if defined(Y_DUAL_STEPPER_DRIVERS) && defined(Y2_STEP_PIN) && Y2_STEP_PIN >= 0
979
+  #if HAS_Y_STEP
980
+    #if defined(Y_DUAL_STEPPER_DRIVERS) && HAS_Y2_STEP
981
       Y2_STEP_INIT;
981
       Y2_STEP_INIT;
982
       Y2_STEP_WRITE(INVERT_Y_STEP_PIN);
982
       Y2_STEP_WRITE(INVERT_Y_STEP_PIN);
983
     #endif
983
     #endif
984
     AXIS_INIT(y, Y, Y);
984
     AXIS_INIT(y, Y, Y);
985
   #endif
985
   #endif
986
-  #if defined(Z_STEP_PIN) && Z_STEP_PIN >= 0
987
-    #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_STEP_PIN) && Z2_STEP_PIN >= 0
986
+  #if HAS_Z_STEP
987
+    #if defined(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_STEP
988
       Z2_STEP_INIT;
988
       Z2_STEP_INIT;
989
       Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
989
       Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
990
     #endif
990
     #endif
991
     AXIS_INIT(z, Z, Z);
991
     AXIS_INIT(z, Z, Z);
992
   #endif
992
   #endif
993
-  #if defined(E0_STEP_PIN) && E0_STEP_PIN >= 0
993
+  #if HAS_E0_STEP
994
     E_AXIS_INIT(0);
994
     E_AXIS_INIT(0);
995
   #endif
995
   #endif
996
-  #if defined(E1_STEP_PIN) && E1_STEP_PIN >= 0
996
+  #if HAS_E1_STEP
997
     E_AXIS_INIT(1);
997
     E_AXIS_INIT(1);
998
   #endif
998
   #endif
999
-  #if defined(E2_STEP_PIN) && E2_STEP_PIN >= 0
999
+  #if HAS_E2_STEP
1000
     E_AXIS_INIT(2);
1000
     E_AXIS_INIT(2);
1001
   #endif
1001
   #endif
1002
-  #if defined(E3_STEP_PIN) && E3_STEP_PIN >= 0
1002
+  #if HAS_E3_STEP
1003
     E_AXIS_INIT(3);
1003
     E_AXIS_INIT(3);
1004
   #endif
1004
   #endif
1005
 
1005
 
1220
 }
1220
 }
1221
 
1221
 
1222
 void microstep_init() {
1222
 void microstep_init() {
1223
-  #if defined(E1_MS1_PIN) && E1_MS1_PIN >= 0
1223
+  #if HAS_MICROSTEPS_E1
1224
     pinMode(E1_MS1_PIN,OUTPUT);
1224
     pinMode(E1_MS1_PIN,OUTPUT);
1225
-    pinMode(E1_MS2_PIN,OUTPUT); 
1225
+    pinMode(E1_MS2_PIN,OUTPUT);
1226
   #endif
1226
   #endif
1227
 
1227
 
1228
-  #if defined(X_MS1_PIN) && X_MS1_PIN >= 0
1228
+  #if HAS_MICROSTEPS
1229
     pinMode(X_MS1_PIN,OUTPUT);
1229
     pinMode(X_MS1_PIN,OUTPUT);
1230
     pinMode(X_MS2_PIN,OUTPUT);  
1230
     pinMode(X_MS2_PIN,OUTPUT);  
1231
     pinMode(Y_MS1_PIN,OUTPUT);
1231
     pinMode(Y_MS1_PIN,OUTPUT);
1246
     case 1: digitalWrite(Y_MS1_PIN, ms1); break;
1246
     case 1: digitalWrite(Y_MS1_PIN, ms1); break;
1247
     case 2: digitalWrite(Z_MS1_PIN, ms1); break;
1247
     case 2: digitalWrite(Z_MS1_PIN, ms1); break;
1248
     case 3: digitalWrite(E0_MS1_PIN, ms1); break;
1248
     case 3: digitalWrite(E0_MS1_PIN, ms1); break;
1249
-    #if defined(E1_MS1_PIN) && E1_MS1_PIN >= 0
1249
+    #if HAS_MICROSTEPS_E1
1250
       case 4: digitalWrite(E1_MS1_PIN, ms1); break;
1250
       case 4: digitalWrite(E1_MS1_PIN, ms1); break;
1251
     #endif
1251
     #endif
1252
   }
1252
   }
1285
   SERIAL_PROTOCOLPGM("E0: ");
1285
   SERIAL_PROTOCOLPGM("E0: ");
1286
   SERIAL_PROTOCOL(digitalRead(E0_MS1_PIN));
1286
   SERIAL_PROTOCOL(digitalRead(E0_MS1_PIN));
1287
   SERIAL_PROTOCOLLN(digitalRead(E0_MS2_PIN));
1287
   SERIAL_PROTOCOLLN(digitalRead(E0_MS2_PIN));
1288
-  #if defined(E1_MS1_PIN) && E1_MS1_PIN >= 0
1288
+  #if HAS_MICROSTEPS_E1
1289
     SERIAL_PROTOCOLPGM("E1: ");
1289
     SERIAL_PROTOCOLPGM("E1: ");
1290
     SERIAL_PROTOCOL(digitalRead(E1_MS1_PIN));
1290
     SERIAL_PROTOCOL(digitalRead(E1_MS1_PIN));
1291
     SERIAL_PROTOCOLLN(digitalRead(E1_MS2_PIN));
1291
     SERIAL_PROTOCOLLN(digitalRead(E1_MS2_PIN));

+ 1
- 1
Marlin/temperature.h View File

53
   extern float redundant_temperature;
53
   extern float redundant_temperature;
54
 #endif
54
 #endif
55
 
55
 
56
-#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
56
+#if HAS_CONTROLLERFAN
57
   extern unsigned char soft_pwm_bed;
57
   extern unsigned char soft_pwm_bed;
58
 #endif
58
 #endif
59
 
59
 

+ 8
- 8
Marlin/ultralcd.h View File

64
 
64
 
65
     #define LCD_CLICKED (buttons&EN_C)
65
     #define LCD_CLICKED (buttons&EN_C)
66
     #ifdef REPRAPWORLD_KEYPAD
66
     #ifdef REPRAPWORLD_KEYPAD
67
-  	  #define EN_REPRAPWORLD_KEYPAD_F3 BIT(BLEN_REPRAPWORLD_KEYPAD_F3)
68
-  	  #define EN_REPRAPWORLD_KEYPAD_F2 BIT(BLEN_REPRAPWORLD_KEYPAD_F2)
69
-  	  #define EN_REPRAPWORLD_KEYPAD_F1 BIT(BLEN_REPRAPWORLD_KEYPAD_F1)
70
-  	  #define EN_REPRAPWORLD_KEYPAD_UP BIT(BLEN_REPRAPWORLD_KEYPAD_UP)
71
-  	  #define EN_REPRAPWORLD_KEYPAD_RIGHT BIT(BLEN_REPRAPWORLD_KEYPAD_RIGHT)
72
-  	  #define EN_REPRAPWORLD_KEYPAD_MIDDLE BIT(BLEN_REPRAPWORLD_KEYPAD_MIDDLE)
73
-  	  #define EN_REPRAPWORLD_KEYPAD_DOWN BIT(BLEN_REPRAPWORLD_KEYPAD_DOWN)
74
-  	  #define EN_REPRAPWORLD_KEYPAD_LEFT BIT(BLEN_REPRAPWORLD_KEYPAD_LEFT)
67
+  	  #define EN_REPRAPWORLD_KEYPAD_F3 (BIT(BLEN_REPRAPWORLD_KEYPAD_F3))
68
+  	  #define EN_REPRAPWORLD_KEYPAD_F2 (BIT(BLEN_REPRAPWORLD_KEYPAD_F2))
69
+  	  #define EN_REPRAPWORLD_KEYPAD_F1 (BIT(BLEN_REPRAPWORLD_KEYPAD_F1))
70
+  	  #define EN_REPRAPWORLD_KEYPAD_UP (BIT(BLEN_REPRAPWORLD_KEYPAD_UP))
71
+  	  #define EN_REPRAPWORLD_KEYPAD_RIGHT (BIT(BLEN_REPRAPWORLD_KEYPAD_RIGHT))
72
+  	  #define EN_REPRAPWORLD_KEYPAD_MIDDLE (BIT(BLEN_REPRAPWORLD_KEYPAD_MIDDLE))
73
+  	  #define EN_REPRAPWORLD_KEYPAD_DOWN (BIT(BLEN_REPRAPWORLD_KEYPAD_DOWN))
74
+  	  #define EN_REPRAPWORLD_KEYPAD_LEFT (BIT(BLEN_REPRAPWORLD_KEYPAD_LEFT))
75
 
75
 
76
   	  #define LCD_CLICKED ((buttons&EN_C) || (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F1))
76
   	  #define LCD_CLICKED ((buttons&EN_C) || (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F1))
77
   	  #define REPRAPWORLD_KEYPAD_MOVE_Z_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F2)
77
   	  #define REPRAPWORLD_KEYPAD_MOVE_Z_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F2)

Loading…
Cancel
Save