Browse Source

Extended condition macros (#13419)

Allow `ENABLED`, `DISABLED`, `PIN_EXISTS`, and `BUTTON_EXISTS` to take multiple arguments. Also add:
- Alias `ANY(...)` for `!DISABLED(...)`
- Alias `ANY_PIN(...)` for `PIN_EXISTS(a) || PIN_EXISTS(b) ...`
- Alias `EITHER(A,B)` for `ANY(...)`
- Alias `ALL(...)` and `BOTH(A,B)` for `ENABLED(...)`
- `NONE(...)` for `DISABLED(...)`
Scott Lahteine 5 years ago
parent
commit
49cf92dc36
No account linked to committer's email address
100 changed files with 384 additions and 372 deletions
  1. 7
    7
      Marlin/Configuration.h
  2. 3
    3
      Marlin/Configuration_adv.h
  3. 1
    1
      Marlin/src/HAL/HAL_AVR/HAL.h
  4. 1
    1
      Marlin/src/HAL/HAL_AVR/fastio_AVR.h
  5. 1
    1
      Marlin/src/HAL/HAL_AVR/persistent_store_eeprom.cpp
  6. 1
    1
      Marlin/src/HAL/HAL_ESP32/HAL.h
  7. 1
    1
      Marlin/src/HAL/HAL_LINUX/spi_pins.h
  8. 1
    1
      Marlin/src/HAL/HAL_LPC1768/main.cpp
  9. 3
    3
      Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp
  10. 1
    1
      Marlin/src/HAL/HAL_STM32F1/persistent_store_flash.cpp
  11. 1
    1
      Marlin/src/HAL/shared/persistent_store_api.cpp
  12. 5
    5
      Marlin/src/Marlin.cpp
  13. 1
    1
      Marlin/src/core/drivers.h
  14. 49
    18
      Marlin/src/core/macros.h
  15. 2
    2
      Marlin/src/core/minmax.h
  16. 2
    2
      Marlin/src/core/utility.cpp
  17. 3
    3
      Marlin/src/core/utility.h
  18. 3
    3
      Marlin/src/feature/bedlevel/bedlevel.cpp
  19. 2
    2
      Marlin/src/feature/bedlevel/bedlevel.h
  20. 1
    1
      Marlin/src/feature/digipot/digipot_mcp4018.cpp
  21. 4
    4
      Marlin/src/feature/leds/leds.cpp
  22. 2
    2
      Marlin/src/feature/leds/leds.h
  23. 1
    1
      Marlin/src/feature/power.cpp
  24. 2
    2
      Marlin/src/feature/solenoid.cpp
  25. 5
    5
      Marlin/src/gcode/bedlevel/abl/G29.cpp
  26. 1
    1
      Marlin/src/gcode/calibrate/G28.cpp
  27. 2
    2
      Marlin/src/gcode/calibrate/G425.cpp
  28. 1
    1
      Marlin/src/gcode/control/M17_M18_M84.cpp
  29. 1
    1
      Marlin/src/gcode/control/M380_M381.cpp
  30. 2
    2
      Marlin/src/gcode/feature/digipot/M907-M910.cpp
  31. 5
    5
      Marlin/src/gcode/gcode.cpp
  32. 4
    4
      Marlin/src/gcode/gcode.h
  33. 1
    1
      Marlin/src/gcode/host/M115.cpp
  34. 2
    2
      Marlin/src/gcode/lcd/M73.cpp
  35. 2
    2
      Marlin/src/gcode/motion/G0_G1.cpp
  36. 1
    1
      Marlin/src/gcode/queue.h
  37. 1
    1
      Marlin/src/gcode/sdcard/M34.cpp
  38. 1
    1
      Marlin/src/gcode/temperature/M104_M109.cpp
  39. 26
    34
      Marlin/src/inc/Conditionals_LCD.h
  40. 34
    34
      Marlin/src/inc/Conditionals_post.h
  41. 41
    41
      Marlin/src/inc/SanityCheck.h
  42. 3
    3
      Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
  43. 1
    1
      Marlin/src/lcd/dogm/status_screen_DOGM.cpp
  44. 1
    1
      Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp
  45. 2
    2
      Marlin/src/lcd/dogm/ultralcd_DOGM.cpp
  46. 2
    2
      Marlin/src/lcd/extensible_ui/ui_api.cpp
  47. 3
    3
      Marlin/src/lcd/menu/menu.cpp
  48. 3
    3
      Marlin/src/lcd/menu/menu.h
  49. 1
    1
      Marlin/src/lcd/menu/menu_advanced.cpp
  50. 2
    2
      Marlin/src/lcd/menu/menu_bed_leveling.cpp
  51. 1
    1
      Marlin/src/lcd/menu/menu_configuration.cpp
  52. 1
    1
      Marlin/src/lcd/menu/menu_delta_calibrate.cpp
  53. 1
    1
      Marlin/src/lcd/menu/menu_led.cpp
  54. 2
    2
      Marlin/src/lcd/menu/menu_main.cpp
  55. 2
    2
      Marlin/src/lcd/menu/menu_motion.cpp
  56. 1
    1
      Marlin/src/lcd/menu/menu_tune.cpp
  57. 8
    8
      Marlin/src/lcd/ultralcd.cpp
  58. 9
    14
      Marlin/src/lcd/ultralcd.h
  59. 1
    1
      Marlin/src/libs/hex_print_routines.cpp
  60. 1
    1
      Marlin/src/libs/least_squares_fit.cpp
  61. 1
    1
      Marlin/src/libs/nozzle.cpp
  62. 11
    11
      Marlin/src/module/configuration_store.cpp
  63. 2
    2
      Marlin/src/module/endstops.cpp
  64. 3
    3
      Marlin/src/module/motion.cpp
  65. 7
    7
      Marlin/src/module/planner.cpp
  66. 3
    3
      Marlin/src/module/planner.h
  67. 2
    2
      Marlin/src/module/printcounter.h
  68. 3
    3
      Marlin/src/module/probe.cpp
  69. 9
    9
      Marlin/src/module/stepper.cpp
  70. 2
    2
      Marlin/src/module/stepper.h
  71. 1
    1
      Marlin/src/module/stepper_indirection.h
  72. 11
    11
      Marlin/src/module/temperature.cpp
  73. 3
    3
      Marlin/src/module/temperature.h
  74. 2
    2
      Marlin/src/module/tool_change.cpp
  75. 1
    1
      Marlin/src/pins/pins.h
  76. 2
    2
      Marlin/src/pins/pins_3DRAG.h
  77. 1
    1
      Marlin/src/pins/pins_ANET_10.h
  78. 2
    2
      Marlin/src/pins/pins_AZTEEG_X3.h
  79. 3
    3
      Marlin/src/pins/pins_AZTEEG_X3_PRO.h
  80. 1
    1
      Marlin/src/pins/pins_AZTEEG_X5_GT.h
  81. 1
    1
      Marlin/src/pins/pins_AZTEEG_X5_MINI_WIFI.h
  82. 2
    2
      Marlin/src/pins/pins_BEAST.h
  83. 2
    2
      Marlin/src/pins/pins_CHITU3D.h
  84. 1
    1
      Marlin/src/pins/pins_FELIX2.h
  85. 1
    3
      Marlin/src/pins/pins_FORMBOT_RAPTOR2.h
  86. 1
    1
      Marlin/src/pins/pins_MEGATRONICS.h
  87. 2
    2
      Marlin/src/pins/pins_MIGHTYBOARD_REVE.h
  88. 1
    1
      Marlin/src/pins/pins_MKS_GEN_13.h
  89. 1
    1
      Marlin/src/pins/pins_MKS_SBASE.h
  90. 2
    2
      Marlin/src/pins/pins_PRINTRBOARD.h
  91. 1
    1
      Marlin/src/pins/pins_PRINTRBOARD_REVF.h
  92. 1
    1
      Marlin/src/pins/pins_RAMBO.h
  93. 10
    12
      Marlin/src/pins/pins_RAMPS.h
  94. 1
    1
      Marlin/src/pins/pins_RAMPS_DUO.h
  95. 1
    1
      Marlin/src/pins/pins_RAMPS_FD_V1.h
  96. 5
    7
      Marlin/src/pins/pins_RAMPS_LINUX.h
  97. 1
    1
      Marlin/src/pins/pins_RAMPS_PLUS.h
  98. 6
    6
      Marlin/src/pins/pins_RAMPS_RE_ARM.h
  99. 1
    1
      Marlin/src/pins/pins_RUMBA.h
  100. 0
    0
      Marlin/src/pins/pins_RURAMPS4D_11.h

+ 7
- 7
Marlin/Configuration.h View File

@@ -218,7 +218,7 @@
218 218
  */
219 219
 //#define MAGNETIC_PARKING_EXTRUDER
220 220
 
221
-#if ENABLED(PARKING_EXTRUDER) || ENABLED(MAGNETIC_PARKING_EXTRUDER)
221
+#if EITHER(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER)
222 222
 
223 223
   #define PARKING_EXTRUDER_PARKING_X { -78, 184 }     // X positions for parking the extruders
224 224
   #define PARKING_EXTRUDER_GRAB_DISTANCE 1            // (mm) Distance to move beyond the parking point to grab the extruder
@@ -1015,7 +1015,7 @@
1015 1015
   #define MAX_SOFTWARE_ENDSTOP_Z
1016 1016
 #endif
1017 1017
 
1018
-#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
1018
+#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
1019 1019
   //#define SOFT_ENDSTOPS_MENU_ITEM  // Enable/Disable software endstops from the LCD
1020 1020
 #endif
1021 1021
 
@@ -1108,7 +1108,7 @@
1108 1108
  */
1109 1109
 //#define DEBUG_LEVELING_FEATURE
1110 1110
 
1111
-#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL)
1111
+#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL)
1112 1112
   // Gradually reduce leveling correction until a set height is reached,
1113 1113
   // at which point movement will be level to the machine's XY plane.
1114 1114
   // The height can be set with M420 Z<height>
@@ -1134,7 +1134,7 @@
1134 1134
 
1135 1135
 #endif
1136 1136
 
1137
-#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
1137
+#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR)
1138 1138
 
1139 1139
   // Set the number of grid points per dimension.
1140 1140
   #define GRID_MAX_POINTS_X 3
@@ -1203,7 +1203,7 @@
1203 1203
  * Points to probe for all 3-point Leveling procedures.
1204 1204
  * Override if the automatically selected points are inadequate.
1205 1205
  */
1206
-#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
1206
+#if EITHER(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL)
1207 1207
   //#define PROBE_PT_1_X 15
1208 1208
   //#define PROBE_PT_1_Y 180
1209 1209
   //#define PROBE_PT_2_X 15
@@ -2037,7 +2037,7 @@
2037 2037
 //#define RGB_LED
2038 2038
 //#define RGBW_LED
2039 2039
 
2040
-#if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
2040
+#if EITHER(RGB_LED, RGBW_LED)
2041 2041
   #define RGB_LED_R_PIN 34
2042 2042
   #define RGB_LED_G_PIN 43
2043 2043
   #define RGB_LED_B_PIN 35
@@ -2066,7 +2066,7 @@
2066 2066
  *  - Change to green once print has finished
2067 2067
  *  - Turn off after the print has finished and the user has pushed a button
2068 2068
  */
2069
-#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(PCA9533)|| ENABLED(NEOPIXEL_LED)
2069
+#if ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED)
2070 2070
   #define PRINTER_EVENT_LEDS
2071 2071
 #endif
2072 2072
 

+ 3
- 3
Marlin/Configuration_adv.h View File

@@ -78,7 +78,7 @@
78 78
   #define THERMAL_PROTECTION_HYSTERESIS 4     // Degrees Celsius
79 79
 
80 80
   //#define ADAPTIVE_FAN_SLOWING              // Slow part cooling fan if temperature drops
81
-  #if ENABLED(ADAPTIVE_FAN_SLOWING) && ENABLED(PIDTEMP)
81
+  #if BOTH(ADAPTIVE_FAN_SLOWING, PIDTEMP)
82 82
     //#define NO_FAN_SLOWING_IN_PID_TUNING    // Don't slow fan speed during M303
83 83
   #endif
84 84
 
@@ -1035,7 +1035,7 @@
1035 1035
 
1036 1036
 // @section leveling
1037 1037
 
1038
-#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
1038
+#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL)
1039 1039
   // Override the mesh area if the automatic (max) area is too large
1040 1040
   //#define MESH_MIN_X MESH_INSET
1041 1041
   //#define MESH_MIN_Y MESH_INSET
@@ -1654,7 +1654,7 @@
1654 1654
    */
1655 1655
   //#define SENSORLESS_PROBING // TMC2130 only
1656 1656
 
1657
-  #if ENABLED(SENSORLESS_HOMING) || ENABLED(SENSORLESS_PROBING)
1657
+  #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
1658 1658
     #define X_STALL_SENSITIVITY  8
1659 1659
     #define Y_STALL_SENSITIVITY  8
1660 1660
     //#define Z_STALL_SENSITIVITY  8

+ 1
- 1
Marlin/src/HAL/HAL_AVR/HAL.h View File

@@ -182,7 +182,7 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t freque
182 182
 #define TIMER_OCR_0             OCR0A
183 183
 #define TIMER_COUNTER_0         TCNT0
184 184
 
185
-#define _CAT(a, ...) a ## __VA_ARGS__
185
+#define _CAT(a,V...) a##V
186 186
 #define HAL_timer_set_compare(timer, compare) (_CAT(TIMER_OCR_, timer) = compare)
187 187
 #define HAL_timer_get_compare(timer) _CAT(TIMER_OCR_, timer)
188 188
 #define HAL_timer_get_count(timer) _CAT(TIMER_COUNTER_, timer)

+ 1
- 1
Marlin/src/HAL/HAL_AVR/fastio_AVR.h View File

@@ -286,7 +286,7 @@ enum ClockSource2 : char {
286 286
   #define PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN)
287 287
 #endif
288 288
 
289
-#if PIN_EXISTS(FAN) || PIN_EXISTS(FAN1) || PIN_EXISTS(FAN2)
289
+#if ANY_PIN(FAN, FAN1, FAN2)
290 290
   #if PIN_EXISTS(FAN2)
291 291
     #define PWM_CHK_FAN_A(P) (P == FAN_PIN || P == FAN1_PIN || P == FAN2_PIN)
292 292
   #elif PIN_EXISTS(FAN1)

+ 1
- 1
Marlin/src/HAL/HAL_AVR/persistent_store_eeprom.cpp View File

@@ -23,7 +23,7 @@
23 23
 
24 24
 #include "../../inc/MarlinConfig.h"
25 25
 
26
-#if ENABLED(EEPROM_SETTINGS) || ENABLED(SD_FIRMWARE_UPDATE)
26
+#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
27 27
 
28 28
 #include "../shared/persistent_store_api.h"
29 29
 

+ 1
- 1
Marlin/src/HAL/HAL_ESP32/HAL.h View File

@@ -36,7 +36,7 @@
36 36
 #include <Arduino.h>
37 37
 
38 38
 #undef DISABLED
39
-#define DISABLED(b) (!_CAT(SWITCH_ENABLED_, b))
39
+#define DISABLED(V...) DO(DIS,&&,V)
40 40
 
41 41
 #include "../shared/math_32bit.h"
42 42
 #include "../shared/HAL_SPI.h"

+ 1
- 1
Marlin/src/HAL/HAL_LINUX/spi_pins.h View File

@@ -23,7 +23,7 @@
23 23
 
24 24
 #include "src/core/macros.h"
25 25
 
26
-#if ENABLED(SDSUPPORT) && ENABLED(DOGLCD) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
26
+#if BOTH(SDSUPPORT, DOGLCD) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
27 27
   #define LPC_SOFTWARE_SPI  // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently
28 28
                             // needed due to the speed and mode requred for communicating with each device being different.
29 29
                             // This requirement can be removed if the SPI access to these devices is updated to use

+ 1
- 1
Marlin/src/HAL/HAL_LPC1768/main.cpp View File

@@ -98,7 +98,7 @@ void HAL_init() {
98 98
 
99 99
 // HAL idle task
100 100
 void HAL_idletask(void) {
101
-  #if ENABLED(SDSUPPORT) && ENABLED(SHARED_SD_CARD)
101
+  #if BOTH(SDSUPPORT, SHARED_SD_CARD)
102 102
     // If Marlin is using the SD card we need to lock it to prevent access from
103 103
     // a PC via USB.
104 104
     // Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but

+ 3
- 3
Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp View File

@@ -55,7 +55,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
55 55
     uint8_t v = *value;
56 56
 
57 57
     // Save to either external EEPROM, program flash or Backup SRAM
58
-    #if ENABLED(SPI_EEPROM) || ENABLED(I2C_EEPROM)
58
+    #if EITHER(SPI_EEPROM, I2C_EEPROM)
59 59
       // EEPROM has only ~100,000 write cycles,
60 60
       // so only write bytes that have changed!
61 61
       uint8_t * const p = (uint8_t * const)pos;
@@ -87,7 +87,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
87 87
   do {
88 88
     // Read from either external EEPROM, program flash or Backup SRAM
89 89
     const uint8_t c = (
90
-      #if ENABLED(SPI_EEPROM) || ENABLED(I2C_EEPROM)
90
+      #if EITHER(SPI_EEPROM, I2C_EEPROM)
91 91
         eeprom_read_byte((uint8_t*)pos)
92 92
       #elif DISABLED(EEPROM_EMULATED_WITH_SRAM)
93 93
         eeprom_buffered_read_byte(pos)
@@ -105,7 +105,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
105 105
 }
106 106
 
107 107
 size_t PersistentStore::capacity() {
108
-  #if ENABLED(SPI_EEPROM) || ENABLED(I2C_EEPROM)
108
+  #if EITHER(SPI_EEPROM, I2C_EEPROM)
109 109
     return E2END + 1;
110 110
   #elif DISABLED(EEPROM_EMULATED_WITH_SRAM)
111 111
     return E2END + 1;

+ 1
- 1
Marlin/src/HAL/HAL_STM32F1/persistent_store_flash.cpp View File

@@ -32,7 +32,7 @@
32 32
 #include "../../inc/MarlinConfig.h"
33 33
 
34 34
 // This is for EEPROM emulation in flash
35
-#if ENABLED(EEPROM_SETTINGS) && ENABLED(FLASH_EEPROM_EMULATION)
35
+#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION)
36 36
 
37 37
 #include "../shared/persistent_store_api.h"
38 38
 

+ 1
- 1
Marlin/src/HAL/shared/persistent_store_api.cpp View File

@@ -22,7 +22,7 @@
22 22
  */
23 23
 #include "../../inc/MarlinConfigPre.h"
24 24
 
25
-#if ENABLED(EEPROM_SETTINGS) || ENABLED(SD_FIRMWARE_UPDATE)
25
+#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
26 26
 
27 27
   #include "persistent_store_api.h"
28 28
   PersistentStore persistentStore;

+ 5
- 5
Marlin/src/Marlin.cpp View File

@@ -128,7 +128,7 @@
128 128
   #include "feature/bedlevel/bedlevel.h"
129 129
 #endif
130 130
 
131
-#if ENABLED(ADVANCED_PAUSE_FEATURE) && ENABLED(PAUSE_PARK_NO_STEPPER_TIMEOUT)
131
+#if BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT)
132 132
   #include "feature/pause.h"
133 133
 #endif
134 134
 
@@ -152,7 +152,7 @@
152 152
   #include "feature/fanmux.h"
153 153
 #endif
154 154
 
155
-#if DO_SWITCH_EXTRUDER || ENABLED(SWITCHING_NOZZLE) || ENABLED(PARKING_EXTRUDER) || ENABLED(MAGNETIC_PARKING_EXTRUDER)
155
+#if DO_SWITCH_EXTRUDER || ANY(SWITCHING_NOZZLE, PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER)
156 156
   #include "module/tool_change.h"
157 157
 #endif
158 158
 
@@ -328,7 +328,7 @@ void disable_all_steppers() {
328 328
       ExtUI::onFilamentRunout(ExtUI::getActiveTool());
329 329
     #endif
330 330
 
331
-    #if ENABLED(HOST_PROMPT_SUPPORT) || ENABLED(HOST_ACTION_COMMANDS)
331
+    #if EITHER(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS)
332 332
       const char tool = '0'
333 333
         #if NUM_RUNOUT_SENSORS > 1
334 334
           + active_extruder
@@ -443,7 +443,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) {
443 443
   }
444 444
 
445 445
   // Prevent steppers timing-out in the middle of M600
446
-  #if ENABLED(ADVANCED_PAUSE_FEATURE) && ENABLED(PAUSE_PARK_NO_STEPPER_TIMEOUT)
446
+  #if BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT)
447 447
     #define MOVE_AWAY_TEST !did_pause_print
448 448
   #else
449 449
     #define MOVE_AWAY_TEST true
@@ -1000,7 +1000,7 @@ void setup() {
1000 1000
     dac_init();
1001 1001
   #endif
1002 1002
 
1003
-  #if (ENABLED(Z_PROBE_SLED) || ENABLED(SOLENOID_PROBE)) && HAS_SOLENOID_1
1003
+  #if EITHER(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1
1004 1004
     OUT_WRITE(SOL1_PIN, LOW); // OFF
1005 1005
   #endif
1006 1006
 

+ 1
- 1
Marlin/src/core/drivers.h View File

@@ -52,7 +52,7 @@
52 52
 #define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T)
53 53
 #define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T)
54 54
 #define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T)
55
-#define AXIS_DRIVER_TYPE_X2(T) ((ENABLED(X_DUAL_STEPPER_DRIVERS) || ENABLED(DUAL_X_CARRIAGE)) && _AXIS_DRIVER_TYPE(X2,T))
55
+#define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T))
56 56
 #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
57 57
 #define AXIS_DRIVER_TYPE_Z2(T) (Z_MULTI_STEPPER_DRIVERS && _AXIS_DRIVER_TYPE(Z2,T))
58 58
 #define AXIS_DRIVER_TYPE_Z3(T) (ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Z3,T))

+ 49
- 18
Marlin/src/core/macros.h View File

@@ -133,8 +133,25 @@
133 133
 
134 134
 #endif
135 135
 
136
+// Macros to chain up to 12 conditions
137
+#define _DO_1(W,C,A)       (_##W##_1(A))
138
+#define _DO_2(W,C,A,B)     (_##W##_1(A) C _##W##_1(B))
139
+#define _DO_3(W,C,A,V...)  (_##W##_1(A) C _DO_2(W,C,V))
140
+#define _DO_4(W,C,A,V...)  (_##W##_1(A) C _DO_3(W,C,V))
141
+#define _DO_5(W,C,A,V...)  (_##W##_1(A) C _DO_4(W,C,V))
142
+#define _DO_6(W,C,A,V...)  (_##W##_1(A) C _DO_5(W,C,V))
143
+#define _DO_7(W,C,A,V...)  (_##W##_1(A) C _DO_6(W,C,V))
144
+#define _DO_8(W,C,A,V...)  (_##W##_1(A) C _DO_7(W,C,V))
145
+#define _DO_9(W,C,A,V...)  (_##W##_1(A) C _DO_8(W,C,V))
146
+#define _DO_10(W,C,A,V...) (_##W##_1(A) C _DO_9(W,C,V))
147
+#define _DO_11(W,C,A,V...) (_##W##_1(A) C _DO_10(W,C,V))
148
+#define _DO_12(W,C,A,V...) (_##W##_1(A) C _DO_11(W,C,V))
149
+#define __DO_N(W,C,N,V...) _DO_##N(W,C,V)
150
+#define _DO_N(W,C,N,V...)  __DO_N(W,C,N,V)
151
+#define DO(W,C,V...)       _DO_N(W,C,NUM_ARGS(V),V)
152
+
136 153
 // Macros to support option testing
137
-#define _CAT(a, ...) a ## __VA_ARGS__
154
+#define _CAT(a,V...) a##V
138 155
 #define SWITCH_ENABLED_false 0
139 156
 #define SWITCH_ENABLED_true  1
140 157
 #define SWITCH_ENABLED_0     0
@@ -142,16 +159,33 @@
142 159
 #define SWITCH_ENABLED_0x0   0
143 160
 #define SWITCH_ENABLED_0x1   1
144 161
 #define SWITCH_ENABLED_      1
145
-#define ENABLED(b) _CAT(SWITCH_ENABLED_, b)
146
-#define DISABLED(b) !ENABLED(b)
147
-
148
-#define WITHIN(V,L,H) ((V) >= (L) && (V) <= (H))
149
-#define NUMERIC(a) WITHIN(a, '0', '9')
150
-#define DECIMAL(a) (NUMERIC(a) || a == '.')
151
-#define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+')
152
-#define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+')
153
-#define COUNT(a) (sizeof(a)/sizeof(*a))
154
-#define ZERO(a) memset(a,0,sizeof(a))
162
+#define _ENA_1(O)           _CAT(SWITCH_ENABLED_, O)
163
+#define _DIS_1(O)           !_ENA_1(O)
164
+#define ENABLED(V...)       DO(ENA,&&,V)
165
+#define DISABLED(V...)      DO(DIS,&&,V)
166
+
167
+#define ANY(V...)          !DISABLED(V)
168
+#define NONE(V...)          DISABLED(V)
169
+#define ALL(V...)           ENABLED(V)
170
+#define BOTH(V1,V2)         ALL(V1,V2)
171
+#define EITHER(V1,V2)       ANY(V1,V2)
172
+
173
+// Macros to support pins/buttons exist testing
174
+#define _PINEX_1(PN)        (defined(PN##_PIN) && PN##_PIN >= 0)
175
+#define PIN_EXISTS(V...)    DO(PINEX,&&,V)
176
+#define ANY_PIN(V...)       DO(PINEX,||,V)
177
+
178
+#define _BTNEX_1(BN)        (defined(BTN_##BN) && BTN_##BN >= 0)
179
+#define BUTTON_EXISTS(V...) DO(BTNEX,&&,V)
180
+#define ANY_BUTTON(V...)    DO(BTNEX,||,V)
181
+
182
+#define WITHIN(N,L,H)       ((N) >= (L) && (N) <= (H))
183
+#define NUMERIC(a)          WITHIN(a, '0', '9')
184
+#define DECIMAL(a)          (NUMERIC(a) || a == '.')
185
+#define NUMERIC_SIGNED(a)   (NUMERIC(a) || (a) == '-' || (a) == '+')
186
+#define DECIMAL_SIGNED(a)   (DECIMAL(a) || (a) == '-' || (a) == '+')
187
+#define COUNT(a)            (sizeof(a)/sizeof(*a))
188
+#define ZERO(a)             memset(a,0,sizeof(a))
155 189
 #define COPY(a,b) do{ \
156 190
     static_assert(sizeof(a[0]) == sizeof(b[0]), "COPY: '" STRINGIFY(a) "' and '" STRINGIFY(b) "' types (sizes) don't match!"); \
157 191
     memcpy(&a[0],&b[0],MIN(sizeof(a),sizeof(b))); \
@@ -165,8 +199,8 @@
165 199
 #define ARRAY_2(v1, v2, ...)                 { v1, v2 }
166 200
 #define ARRAY_1(v1, ...)                     { v1 }
167 201
 
168
-#define _ARRAY_N(N, ...) ARRAY_ ##N(__VA_ARGS__)
169
-#define ARRAY_N(N, ...) _ARRAY_N(N, __VA_ARGS__)
202
+#define _ARRAY_N(N,V...) ARRAY_##N(V)
203
+#define ARRAY_N(N,V...) _ARRAY_N(N,V)
170 204
 
171 205
 // Macros for adding
172 206
 #define INC_0 1
@@ -178,7 +212,7 @@
178 212
 #define INC_6 7
179 213
 #define INC_7 8
180 214
 #define INC_8 9
181
-#define INCREMENT_(n) INC_ ##n
215
+#define INCREMENT_(n) INC_##n
182 216
 #define INCREMENT(n) INCREMENT_(n)
183 217
 
184 218
 // Macros for subtracting
@@ -191,12 +225,9 @@
191 225
 #define DEC_7 6
192 226
 #define DEC_8 7
193 227
 #define DEC_9 8
194
-#define DECREMENT_(n) DEC_ ##n
228
+#define DECREMENT_(n) DEC_##n
195 229
 #define DECREMENT(n) DECREMENT_(n)
196 230
 
197
-#define PIN_EXISTS(PN)    (defined(PN ##_PIN) && PN ##_PIN >= 0)
198
-#define BUTTON_EXISTS(BN) (defined(BTN_## BN) && BTN_## BN >= 0)
199
-
200 231
 #define MMM_TO_MMS(MM_M) ((MM_M)/60.0f)
201 232
 #define MMS_TO_MMM(MM_S) ((MM_S)*60.0f)
202 233
 

+ 2
- 2
Marlin/src/core/minmax.h View File

@@ -23,9 +23,9 @@
23 23
 #undef MIN
24 24
 #undef MAX
25 25
 
26
-// Pass NUM_ARGS(__VA_ARGS__) to use the number of arguments
26
+// Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments
27 27
 #define _NUM_ARGS(_0,_24_,_23,_22,_21,_20,_19,_18,_17,_16,_15,_14,_13,_12,_11,_10,_9,_8,_7,_6,_5,_4,_3,_2,_1,N,...) N
28
-#define NUM_ARGS(...) _NUM_ARGS(0, __VA_ARGS__ ,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
28
+#define NUM_ARGS(V...) _NUM_ARGS(0,V,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
29 29
 
30 30
 #ifdef __cplusplus
31 31
 

+ 2
- 2
Marlin/src/core/utility.cpp View File

@@ -35,7 +35,7 @@ void safe_delay(millis_t ms) {
35 35
   thermalManager.manage_heater(); // This keeps us safe if too many small safe_delay() calls are made
36 36
 }
37 37
 
38
-#if ENABLED(EEPROM_SETTINGS) || ENABLED(SD_FIRMWARE_UPDATE)
38
+#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
39 39
 
40 40
   void crc16(uint16_t *crc, const void * const data, uint16_t cnt) {
41 41
     uint8_t *ptr = (uint8_t *)data;
@@ -48,7 +48,7 @@ void safe_delay(millis_t ms) {
48 48
 
49 49
 #endif // EEPROM_SETTINGS || SD_FIRMWARE_UPDATE
50 50
 
51
-#if ENABLED(ULTRA_LCD) || ENABLED(DEBUG_LEVELING_FEATURE) || ENABLED(EXTENSIBLE_UI)
51
+#if ANY(ULTRA_LCD, DEBUG_LEVELING_FEATURE, EXTENSIBLE_UI)
52 52
 
53 53
   char conv[8] = { 0 };
54 54
 

+ 3
- 3
Marlin/src/core/utility.h View File

@@ -37,11 +37,11 @@ inline void serial_delay(const millis_t ms) {
37 37
   #endif
38 38
 }
39 39
 
40
-#if ENABLED(EEPROM_SETTINGS) || ENABLED(SD_FIRMWARE_UPDATE)
40
+#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
41 41
   void crc16(uint16_t *crc, const void * const data, uint16_t cnt);
42 42
 #endif
43 43
 
44
-#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(G26_MESH_VALIDATION)
44
+#if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION)
45 45
   /**
46 46
    * These support functions allow the use of large bit arrays of flags that take very
47 47
    * little RAM. Currently they are limited to being 16x16 in size. Changing the declaration
@@ -53,7 +53,7 @@ inline void serial_delay(const millis_t ms) {
53 53
   FORCE_INLINE bool is_bitmap_set(uint16_t bits[16], const uint8_t x, const uint8_t y) { return TEST(bits[y], x); }
54 54
 #endif
55 55
 
56
-#if ENABLED(ULTRA_LCD) || ENABLED(DEBUG_LEVELING_FEATURE) || ENABLED(EXTENSIBLE_UI)
56
+#if ANY(ULTRA_LCD, DEBUG_LEVELING_FEATURE, EXTENSIBLE_UI)
57 57
 
58 58
   // Convert uint8_t to string with 123 format
59 59
   char* ui8tostr3(const uint8_t x);

+ 3
- 3
Marlin/src/feature/bedlevel/bedlevel.cpp View File

@@ -27,7 +27,7 @@
27 27
 #include "bedlevel.h"
28 28
 #include "../../module/planner.h"
29 29
 
30
-#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
30
+#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY)
31 31
   #include "../../module/motion.h"
32 32
 #endif
33 33
 
@@ -146,7 +146,7 @@ void reset_bed_level() {
146 146
   #endif
147 147
 }
148 148
 
149
-#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(MESH_BED_LEVELING)
149
+#if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING)
150 150
 
151 151
   /**
152 152
    * Enable to produce output in JSON format suitable
@@ -215,7 +215,7 @@ void reset_bed_level() {
215 215
 
216 216
 #endif // AUTO_BED_LEVELING_BILINEAR || MESH_BED_LEVELING
217 217
 
218
-#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
218
+#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY)
219 219
 
220 220
   void _manual_goto_xy(const float &rx, const float &ry) {
221 221
 

+ 2
- 2
Marlin/src/feature/bedlevel/bedlevel.h View File

@@ -48,7 +48,7 @@ void reset_bed_level();
48 48
   void set_z_fade_height(const float zfh, const bool do_report=true);
49 49
 #endif
50 50
 
51
-#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(MESH_BED_LEVELING)
51
+#if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING)
52 52
 
53 53
   #include <stdint.h>
54 54
 
@@ -61,7 +61,7 @@ void reset_bed_level();
61 61
 
62 62
 #endif
63 63
 
64
-#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
64
+#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY)
65 65
   void _manual_goto_xy(const float &x, const float &y);
66 66
 #endif
67 67
 

+ 1
- 1
Marlin/src/feature/digipot/digipot_mcp4018.cpp View File

@@ -22,7 +22,7 @@
22 22
 
23 23
 #include "../../inc/MarlinConfig.h"
24 24
 
25
-#if ENABLED(DIGIPOT_I2C) && ENABLED(DIGIPOT_MCP4018)
25
+#if BOTH(DIGIPOT_I2C, DIGIPOT_MCP4018)
26 26
 
27 27
 #include "../../core/enum.h"
28 28
 #include "Stream.h"

+ 4
- 4
Marlin/src/feature/leds/leds.cpp View File

@@ -52,7 +52,7 @@
52 52
   );
53 53
 #endif
54 54
 
55
-#if ENABLED(LED_CONTROL_MENU) || ENABLED(PRINTER_EVENT_LEDS)
55
+#if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS)
56 56
   LEDColor LEDLights::color;
57 57
   bool LEDLights::lights_on;
58 58
 #endif
@@ -60,7 +60,7 @@
60 60
 LEDLights leds;
61 61
 
62 62
 void LEDLights::setup() {
63
-  #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
63
+  #if EITHER(RGB_LED, RGBW_LED)
64 64
     if (PWM_PIN(RGB_LED_R_PIN)) SET_PWM(RGB_LED_R_PIN); else SET_OUTPUT(RGB_LED_R_PIN);
65 65
     if (PWM_PIN(RGB_LED_G_PIN)) SET_PWM(RGB_LED_G_PIN); else SET_OUTPUT(RGB_LED_G_PIN);
66 66
     if (PWM_PIN(RGB_LED_B_PIN)) SET_PWM(RGB_LED_B_PIN); else SET_OUTPUT(RGB_LED_B_PIN);
@@ -108,7 +108,7 @@ void LEDLights::set_color(const LEDColor &incol
108 108
 
109 109
   #endif
110 110
 
111
-  #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
111
+  #if EITHER(RGB_LED, RGBW_LED)
112 112
 
113 113
     // This variant uses 3-4 separate pins for the RGB(W) components.
114 114
     // If the pins can do PWM then their intensity will be set.
@@ -131,7 +131,7 @@ void LEDLights::set_color(const LEDColor &incol
131 131
     RGBsetColor(incol.r, incol.g, incol.b, true);
132 132
   #endif
133 133
 
134
-  #if ENABLED(LED_CONTROL_MENU) || ENABLED(PRINTER_EVENT_LEDS)
134
+  #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS)
135 135
     // Don't update the color when OFF
136 136
     lights_on = !incol.is_off();
137 137
     if (lights_on) color = incol;

+ 2
- 2
Marlin/src/feature/leds/leds.h View File

@@ -33,7 +33,7 @@
33 33
   #include "neopixel.h"
34 34
 #endif
35 35
 
36
-#define HAS_WHITE_LED (ENABLED(RGBW_LED) || ENABLED(NEOPIXEL_LED))
36
+#define HAS_WHITE_LED EITHER(RGBW_LED, NEOPIXEL_LED)
37 37
 
38 38
 /**
39 39
  * LEDcolor type for use with leds.set_color
@@ -183,7 +183,7 @@ public:
183 183
     static inline LEDColor get_color() { return lights_on ? color : LEDColorOff(); }
184 184
   #endif
185 185
 
186
-  #if ENABLED(LED_CONTROL_MENU) || ENABLED(PRINTER_EVENT_LEDS)
186
+  #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS)
187 187
     static LEDColor color; // last non-off color
188 188
     static bool lights_on; // the last set color was "on"
189 189
   #endif

+ 1
- 1
Marlin/src/feature/power.cpp View File

@@ -46,7 +46,7 @@ bool Power::is_power_needed() {
46 46
     HOTEND_LOOP() if (thermalManager.autofan_speed[e]) return true;
47 47
   #endif
48 48
 
49
-  #if ENABLED(AUTO_POWER_CONTROLLERFAN) && HAS_CONTROLLER_FAN && ENABLED(USE_CONTROLLER_FAN)
49
+  #if ENABLED(AUTO_POWER_CONTROLLERFAN, USE_CONTROLLER_FAN) && HAS_CONTROLLER_FAN
50 50
     if (controllerfan_speed) return true;
51 51
   #endif
52 52
 

+ 2
- 2
Marlin/src/feature/solenoid.cpp View File

@@ -22,7 +22,7 @@
22 22
 
23 23
 #include "../inc/MarlinConfig.h"
24 24
 
25
-#if ENABLED(EXT_SOLENOID) || ENABLED(MANUAL_SOLENOID_CONTROL)
25
+#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL)
26 26
 
27 27
 #include "solenoid.h"
28 28
 
@@ -95,4 +95,4 @@ void disable_all_solenoids() {
95 95
   #endif
96 96
 }
97 97
 
98
-#endif // EXT_SOLENOID
98
+#endif // EXT_SOLENOID || MANUAL_SOLENOID_CONTROL

+ 5
- 5
Marlin/src/gcode/bedlevel/abl/G29.cpp View File

@@ -36,7 +36,7 @@
36 36
 #include "../../../module/probe.h"
37 37
 #include "../../queue.h"
38 38
 
39
-#if ENABLED(LCD_BED_LEVELING) && ENABLED(PROBE_MANUALLY)
39
+#if BOTH(LCD_BED_LEVELING, PROBE_MANUALLY)
40 40
   #include "../../../lcd/ultralcd.h"
41 41
 #endif
42 42
 
@@ -151,7 +151,7 @@
151 151
  */
152 152
 G29_TYPE GcodeSuite::G29() {
153 153
 
154
-  #if ENABLED(DEBUG_LEVELING_FEATURE) || ENABLED(PROBE_MANUALLY)
154
+  #if EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY)
155 155
     const bool seenQ = parser.seen('Q');
156 156
   #else
157 157
     constexpr bool seenQ = false;
@@ -205,7 +205,7 @@ G29_TYPE GcodeSuite::G29() {
205 205
   ABL_VAR float xProbe, yProbe, measured_z;
206 206
   ABL_VAR bool dryrun, abl_should_enable;
207 207
 
208
-  #if ENABLED(PROBE_MANUALLY) || ENABLED(AUTO_BED_LEVELING_LINEAR)
208
+  #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR)
209 209
     ABL_VAR int abl_probe_index;
210 210
   #endif
211 211
 
@@ -280,7 +280,7 @@ G29_TYPE GcodeSuite::G29() {
280 280
       if (active_extruder != 0) tool_change(0);
281 281
     #endif
282 282
 
283
-    #if ENABLED(PROBE_MANUALLY) || ENABLED(AUTO_BED_LEVELING_LINEAR)
283
+    #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR)
284 284
       abl_probe_index = -1;
285 285
     #endif
286 286
 
@@ -522,7 +522,7 @@ G29_TYPE GcodeSuite::G29() {
522 522
     }
523 523
     else {
524 524
 
525
-      #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT)
525
+      #if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT)
526 526
         const uint16_t index = abl_probe_index - 1;
527 527
       #endif
528 528
 

+ 1
- 1
Marlin/src/gcode/calibrate/G28.cpp View File

@@ -400,7 +400,7 @@ void GcodeSuite::G28(const bool always_home_all) {
400 400
 
401 401
   endstops.not_homing();
402 402
 
403
-  #if ENABLED(DELTA) && ENABLED(DELTA_HOME_TO_SAFE_ZONE)
403
+  #if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE)
404 404
     // move to a height where we can use the full xy-area
405 405
     do_blocking_move_to_z(delta_clip_start_height);
406 406
   #endif

+ 2
- 2
Marlin/src/gcode/calibrate/G425.cpp View File

@@ -52,8 +52,8 @@
52 52
   #define CALIBRATION_MEASUREMENT_CERTAIN   0.5 // mm
53 53
 #endif
54 54
 
55
-#define HAS_X_CENTER (ENABLED(CALIBRATION_MEASURE_LEFT)  && ENABLED(CALIBRATION_MEASURE_RIGHT))
56
-#define HAS_Y_CENTER (ENABLED(CALIBRATION_MEASURE_FRONT) && ENABLED(CALIBRATION_MEASURE_BACK))
55
+#define HAS_X_CENTER BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT)
56
+#define HAS_Y_CENTER BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK)
57 57
 
58 58
 #if ENABLED(BACKLASH_GCODE)
59 59
   extern float backlash_distance_mm[], backlash_correction, backlash_smoothing_mm;

+ 1
- 1
Marlin/src/gcode/control/M17_M18_M84.cpp View File

@@ -25,7 +25,7 @@
25 25
 #include "../../lcd/ultralcd.h"
26 26
 #include "../../module/stepper.h"
27 27
 
28
-#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD)
28
+#if BOTH(AUTO_BED_LEVELING_UBL, ULTRA_LCD)
29 29
   #include "../../feature/bedlevel/bedlevel.h"
30 30
 #endif
31 31
 

+ 1
- 1
Marlin/src/gcode/control/M380_M381.cpp View File

@@ -22,7 +22,7 @@
22 22
 
23 23
 #include "../../inc/MarlinConfig.h"
24 24
 
25
-#if ENABLED(EXT_SOLENOID) || ENABLED(MANUAL_SOLENOID_CONTROL)
25
+#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL)
26 26
 
27 27
 #include "../gcode.h"
28 28
 #include "../../feature/solenoid.h"

+ 2
- 2
Marlin/src/gcode/feature/digipot/M907-M910.cpp View File

@@ -22,7 +22,7 @@
22 22
 
23 23
 #include "../../../inc/MarlinConfig.h"
24 24
 
25
-#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || ENABLED(DIGIPOT_I2C) || ENABLED(DAC_STEPPER_CURRENT)
25
+#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT)
26 26
 
27 27
 #include "../../gcode.h"
28 28
 
@@ -50,7 +50,7 @@ void GcodeSuite::M907() {
50 50
 
51 51
   #elif HAS_MOTOR_CURRENT_PWM
52 52
 
53
-    #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) || PIN_EXISTS(MOTOR_CURRENT_PWM_Y) || PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
53
+    #if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY)
54 54
       if (parser.seenval('X') || parser.seenval('Y')) stepper.digipot_current(0, parser.value_int());
55 55
     #endif
56 56
     #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)

+ 5
- 5
Marlin/src/gcode/gcode.cpp View File

@@ -117,7 +117,7 @@ void GcodeSuite::get_destination_from_command() {
117 117
   #endif
118 118
 
119 119
   // Get ABCDHI mixing factors
120
-  #if ENABLED(MIXING_EXTRUDER) && ENABLED(DIRECT_MIXING_IN_G1)
120
+  #if BOTH(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1)
121 121
     M165();
122 122
   #endif
123 123
 }
@@ -330,7 +330,7 @@ void GcodeSuite::process_parsed_command(
330 330
           case 33: M33(); break;                                  // M33: Get the long full path to a file or folder
331 331
         #endif
332 332
 
333
-        #if ENABLED(SDCARD_SORT_ALPHA) && ENABLED(SDSORT_GCODE)
333
+        #if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE)
334 334
           case 34: M34(); break;                                  // M34: Set SD card sorting options
335 335
         #endif
336 336
 
@@ -494,7 +494,7 @@ void GcodeSuite::process_parsed_command(
494 494
         case 665: M665(); break;                                  // M665: Set delta configurations
495 495
       #endif
496 496
 
497
-      #if ENABLED(DELTA) || ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
497
+      #if ANY(DELTA, X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_DUAL_ENDSTOPS)
498 498
         case 666: M666(); break;                                  // M666: Set delta or dual endstop adjustment
499 499
       #endif
500 500
 
@@ -576,7 +576,7 @@ void GcodeSuite::process_parsed_command(
576 576
         case 364: if (M364()) return; break;                      // M364: SCARA Psi pos3 (90 deg to Theta)
577 577
       #endif
578 578
 
579
-      #if ENABLED(EXT_SOLENOID) || ENABLED(MANUAL_SOLENOID_CONTROL)
579
+      #if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL)
580 580
         case 380: M380(); break;                                  // M380: Activate solenoid on active (or specified) extruder
581 581
         case 381: M381(); break;                                  // M381: Disable all solenoids or, if MANUAL_SOLENOID_CONTROL, active (or specified) solenoid
582 582
       #endif
@@ -673,7 +673,7 @@ void GcodeSuite::process_parsed_command(
673 673
         case 900: M900(); break;                                  // M900: Set advance K factor.
674 674
       #endif
675 675
 
676
-      #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || ENABLED(DIGIPOT_I2C) || ENABLED(DAC_STEPPER_CURRENT)
676
+      #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT)
677 677
         case 907: M907(); break;                                  // M907: Set digital trimpot motor current using axis codes.
678 678
         #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
679 679
           case 908: M908(); break;                                // M908: Control digital trimpot directly.

+ 4
- 4
Marlin/src/gcode/gcode.h View File

@@ -144,7 +144,7 @@
144 144
  * M140 - Set bed target temp. S<temp>
145 145
  * M145 - Set heatup values for materials on the LCD. H<hotend> B<bed> F<fan speed> for S<material> (0=PLA, 1=ABS)
146 146
  * M149 - Set temperature units. (Requires TEMPERATURE_UNITS_SUPPORT)
147
- * M150 - Set Status LED Color as R<red> U<green> B<blue> P<bright>. Values 0-255. (Requires BLINKM, RGB_LED, RGBW_LED, NEOPIXEL_LED, or PCA9632).
147
+ * M150 - Set Status LED Color as R<red> U<green> B<blue> P<bright>. Values 0-255. (Requires BLINKM, RGB_LED, RGBW_LED, NEOPIXEL_LED, PCA9533, or PCA9632).
148 148
  * M155 - Auto-report temperatures with interval of S<seconds>. (Requires AUTO_REPORT_TEMPERATURES)
149 149
  * M163 - Set a single proportion for a mixing extruder. (Requires MIXING_EXTRUDER)
150 150
  * M164 - Commit the mix and save to a virtual tool (current, or as specified by 'S'). (Requires MIXING_EXTRUDER)
@@ -480,7 +480,7 @@ private:
480 480
     #if ENABLED(LONG_FILENAME_HOST_SUPPORT)
481 481
       static void M33();
482 482
     #endif
483
-    #if ENABLED(SDCARD_SORT_ALPHA) && ENABLED(SDSORT_GCODE)
483
+    #if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE)
484 484
       static void M34();
485 485
     #endif
486 486
   #endif
@@ -706,7 +706,7 @@ private:
706 706
     static bool M364();
707 707
   #endif
708 708
 
709
-  #if ENABLED(EXT_SOLENOID) || ENABLED(MANUAL_SOLENOID_CONTROL)
709
+  #if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL)
710 710
     static void M380();
711 711
     static void M381();
712 712
   #endif
@@ -845,7 +845,7 @@ private:
845 845
     static void M918();
846 846
   #endif
847 847
 
848
-  #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || ENABLED(DIGIPOT_I2C) || ENABLED(DAC_STEPPER_CURRENT)
848
+  #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM || EITHER(DIGIPOT_I2C, DAC_STEPPER_CURRENT)
849 849
     static void M907();
850 850
     #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
851 851
       static void M908();

+ 1
- 1
Marlin/src/gcode/host/M115.cpp View File

@@ -152,7 +152,7 @@ void GcodeSuite::M115() {
152 152
 
153 153
     // THERMAL_PROTECTION
154 154
     cap_line(PSTR("THERMAL_PROTECTION")
155
-      #if ENABLED(THERMAL_PROTECTION_HOTENDS) && ENABLED(THERMAL_PROTECTION_BED)
155
+      #if BOTH(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_BED)
156 156
         , true
157 157
       #endif
158 158
     );

+ 2
- 2
Marlin/src/gcode/lcd/M73.cpp View File

@@ -22,7 +22,7 @@
22 22
 
23 23
 #include "../../inc/MarlinConfig.h"
24 24
 
25
-#if ENABLED(LCD_SET_PROGRESS_MANUALLY) && (ENABLED(EXTENSIBLE_UI) || ENABLED(ULTRA_LCD))
25
+#if ENABLED(LCD_SET_PROGRESS_MANUALLY) && EITHER(EXTENSIBLE_UI, ULTRA_LCD)
26 26
 
27 27
 #include "../gcode.h"
28 28
 #include "../../lcd/ultralcd.h"
@@ -42,4 +42,4 @@ void GcodeSuite::M73() {
42 42
     ui.set_progress(parser.value_byte());
43 43
 }
44 44
 
45
-#endif // LCD_SET_PROGRESS_MANUALLY && (ENABLED(EXTENSIBLE_UI) || ENABLED(ULTRA_LCD))
45
+#endif // LCD_SET_PROGRESS_MANUALLY && (EXTENSIBLE_UI || ULTRA_LCD)

+ 2
- 2
Marlin/src/gcode/motion/G0_G1.cpp View File

@@ -25,7 +25,7 @@
25 25
 
26 26
 #include "../../Marlin.h"
27 27
 
28
-#if ENABLED(FWRETRACT) && ENABLED(FWRETRACT_AUTORETRACT)
28
+#if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT)
29 29
   #include "../../feature/fwretract.h"
30 30
 #endif
31 31
 
@@ -79,7 +79,7 @@ void GcodeSuite::G0_G1(
79 79
       }
80 80
     #endif
81 81
 
82
-    #if ENABLED(FWRETRACT) && ENABLED(FWRETRACT_AUTORETRACT)
82
+    #if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT)
83 83
 
84 84
       if (MIN_AUTORETRACT <= MAX_AUTORETRACT) {
85 85
         // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves

+ 1
- 1
Marlin/src/gcode/queue.h View File

@@ -95,7 +95,7 @@ void enqueue_and_echo_commands_P(PGM_P const pgcode);
95 95
  */
96 96
 bool enqueue_and_echo_command(const char* cmd);
97 97
 
98
-#define HAS_LCD_QUEUE_NOW (ENABLED(MALYAN_LCD) || (HAS_LCD_MENU && (ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(PID_AUTOTUNE_MENU) || ENABLED(ADVANCED_PAUSE_FEATURE))))
98
+#define HAS_LCD_QUEUE_NOW (ENABLED(MALYAN_LCD) || (HAS_LCD_MENU && ANY(AUTO_BED_LEVELING_UBL, PID_AUTOTUNE_MENU, ADVANCED_PAUSE_FEATURE)))
99 99
 #define HAS_QUEUE_NOW (ENABLED(SDSUPPORT) || HAS_LCD_QUEUE_NOW)
100 100
 
101 101
 #if HAS_QUEUE_NOW

+ 1
- 1
Marlin/src/gcode/sdcard/M34.cpp View File

@@ -22,7 +22,7 @@
22 22
 
23 23
 #include "../../inc/MarlinConfig.h"
24 24
 
25
-#if ENABLED(SDCARD_SORT_ALPHA) && ENABLED(SDSORT_GCODE)
25
+#if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE)
26 26
 
27 27
 #include "../gcode.h"
28 28
 #include "../../sd/cardreader.h"

+ 1
- 1
Marlin/src/gcode/temperature/M104_M109.cpp View File

@@ -125,7 +125,7 @@ void GcodeSuite::M109() {
125 125
         print_job_timer.start();
126 126
     #endif
127 127
 
128
-    #if ENABLED(ULTRA_LCD) || ENABLED(EXTENSIBLE_UI)
128
+    #if EITHER(ULTRA_LCD, EXTENSIBLE_UI)
129 129
       if (thermalManager.isHeatingHotend(target_extruder) || !no_wait_for_cooling)
130 130
         thermalManager.set_heating_message(target_extruder);
131 131
     #endif

+ 26
- 34
Marlin/src/inc/Conditionals_LCD.h View File

@@ -64,7 +64,7 @@
64 64
 
65 65
   #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
66 66
 
67
-#elif ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) || ENABLED(AZSMZ_12864)
67
+#elif ANY(miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864)
68 68
 
69 69
   #define ULTRA_LCD
70 70
   #define DOGLCD
@@ -141,7 +141,7 @@
141 141
 
142 142
 #endif
143 143
 
144
-#if ENABLED(MAKRPANEL) || ENABLED(MINIPANEL)
144
+#if EITHER(MAKRPANEL, MINIPANEL)
145 145
   #define DOGLCD
146 146
   #define ULTIPANEL
147 147
   #define DEFAULT_LCD_CONTRAST 17
@@ -159,13 +159,13 @@
159 159
 #endif
160 160
 
161 161
 // 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106
162
-#define HAS_SSD1306_OLED_I2C (ENABLED(U8GLIB_SSD1306) || ENABLED(U8GLIB_SSD1309) || ENABLED(U8GLIB_SH1106))
162
+#define HAS_SSD1306_OLED_I2C ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106)
163 163
 #if HAS_SSD1306_OLED_I2C
164 164
   #define ULTRA_LCD
165 165
   #define DOGLCD
166 166
 #endif
167 167
 
168
-#if ENABLED(PANEL_ONE) || ENABLED(U8GLIB_SH1106)
168
+#if EITHER(PANEL_ONE, U8GLIB_SH1106)
169 169
 
170 170
   #define ULTIMAKERCONTROLLER
171 171
 
@@ -177,17 +177,13 @@
177 177
 
178 178
 #endif
179 179
 
180
-#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI) || ENABLED(SILVER_GATE_GLCD_CONTROLLER)
180
+#if ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER)
181 181
   #define DOGLCD
182 182
   #define U8GLIB_ST7920
183 183
   #define REPRAP_DISCOUNT_SMART_CONTROLLER
184 184
 #endif
185 185
 
186
-#if ENABLED(ULTIMAKERCONTROLLER)              \
187
- || ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \
188
- || ENABLED(G3D_PANEL)                        \
189
- || ENABLED(RIGIDBOT_PANEL)                   \
190
- || ENABLED(ULTI_CONTROLLER)
186
+#if ANY(ULTIMAKERCONTROLLER, REPRAP_DISCOUNT_SMART_CONTROLLER, G3D_PANEL, RIGIDBOT_PANEL, ULTI_CONTROLLER)
191 187
   #define ULTIPANEL
192 188
 #endif
193 189
 
@@ -223,7 +219,7 @@
223 219
  * I2C PANELS
224 220
  */
225 221
 
226
-#if ENABLED(LCD_SAINSMART_I2C_1602) || ENABLED(LCD_SAINSMART_I2C_2004)
222
+#if EITHER(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004)
227 223
 
228 224
   #define LCD_I2C_TYPE_PCF8575
229 225
   #define LCD_I2C_ADDRESS 0x27   // I2C Address of the port expander
@@ -267,15 +263,11 @@
267 263
   #define STD_ENCODER_PULSES_PER_STEP 2
268 264
   #define STD_ENCODER_STEPS_PER_MENU_ITEM 1
269 265
 
270
-#elif ENABLED(miniVIKI) || ENABLED(VIKI2) \
271
-   || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
272
-   || ENABLED(AZSMZ_12864) \
273
-   || ENABLED(OLED_PANEL_TINYBOY2) \
274
-   || ENABLED(BQ_LCD_SMART_CONTROLLER) \
275
-   || ENABLED(LCD_I2C_PANELOLU2) \
276
-   || ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
266
+#elif ANY(miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, OLED_PANEL_TINYBOY2, BQ_LCD_SMART_CONTROLLER, LCD_I2C_PANELOLU2, REPRAP_DISCOUNT_SMART_CONTROLLER)
267
+
277 268
   #define STD_ENCODER_PULSES_PER_STEP 4
278 269
   #define STD_ENCODER_STEPS_PER_MENU_ITEM 1
270
+
279 271
 #endif
280 272
 
281 273
 #ifndef STD_ENCODER_PULSES_PER_STEP
@@ -400,16 +392,16 @@
400 392
 #endif
401 393
 
402 394
 // No inactive extruders with MK2_MULTIPLEXER or SWITCHING_NOZZLE
403
-#if ENABLED(MK2_MULTIPLEXER) || ENABLED(SWITCHING_NOZZLE)
395
+#if EITHER(MK2_MULTIPLEXER, SWITCHING_NOZZLE)
404 396
   #undef DISABLE_INACTIVE_EXTRUDER
405 397
 #endif
406 398
 
407 399
 // Prusa MK2 Multiplexer and MMU 2.0 force SINGLENOZZLE
408
-#if ENABLED(MK2_MULTIPLEXER) || ENABLED(PRUSA_MMU2)
400
+#if EITHER(MK2_MULTIPLEXER, PRUSA_MMU2)
409 401
   #define SINGLENOZZLE
410 402
 #endif
411 403
 
412
-#if ENABLED(SINGLENOZZLE) || ENABLED(MIXING_EXTRUDER)         // One hotend, one thermistor, no XY offset
404
+#if EITHER(SINGLENOZZLE, MIXING_EXTRUDER)         // One hotend, one thermistor, no XY offset
413 405
   #undef HOTENDS
414 406
   #define HOTENDS       1
415 407
   #undef TEMP_SENSOR_1_AS_REDUNDANT
@@ -435,7 +427,7 @@
435 427
 #define SWITCHING_NOZZLE_TWO_SERVOS defined(SWITCHING_NOZZLE_E1_SERVO_NR)
436 428
 
437 429
 #define HAS_HOTEND_OFFSET (HOTENDS > 1)
438
-#define HAS_DUPLICATION_MODE (ENABLED(DUAL_X_CARRIAGE) || ENABLED(MULTI_NOZZLE_DUPLICATION))
430
+#define HAS_DUPLICATION_MODE EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION)
439 431
 
440 432
 /**
441 433
  * DISTINCT_E_FACTORS affects how some E factors are accessed
@@ -506,8 +498,8 @@
506 498
 /**
507 499
  * Set flags for enabled probes
508 500
  */
509
-#define HAS_BED_PROBE (ENABLED(FIX_MOUNTED_PROBE) || ENABLED(Z_PROBE_ALLEN_KEY) || HAS_Z_SERVO_PROBE || ENABLED(Z_PROBE_SLED) || ENABLED(SOLENOID_PROBE) || ENABLED(SENSORLESS_PROBING) || ENABLED(RACK_AND_PINION_PROBE))
510
-#define PROBE_SELECTED (HAS_BED_PROBE || ENABLED(PROBE_MANUALLY) || ENABLED(MESH_BED_LEVELING))
501
+#define HAS_BED_PROBE (HAS_Z_SERVO_PROBE || ANY(FIX_MOUNTED_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, SOLENOID_PROBE, SENSORLESS_PROBING, RACK_AND_PINION_PROBE))
502
+#define PROBE_SELECTED (HAS_BED_PROBE || EITHER(PROBE_MANUALLY, MESH_BED_LEVELING))
511 503
 
512 504
 #if HAS_BED_PROBE
513 505
   #define USES_Z_MIN_PROBE_ENDSTOP DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
@@ -528,19 +520,19 @@
528 520
   #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y))
529 521
 #endif
530 522
 
531
-#define HAS_SOFTWARE_ENDSTOPS (ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS))
532
-#define HAS_RESUME_CONTINUE (ENABLED(EXTENSIBLE_UI) || ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER))
533
-#define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(PCA9533) || ENABLED(NEOPIXEL_LED))
534
-#define HAS_LEDS_OFF_FLAG (ENABLED(PRINTER_EVENT_LEDS) && ENABLED(SDSUPPORT) && HAS_RESUME_CONTINUE)
535
-#define HAS_PRINT_PROGRESS (ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY))
523
+#define HAS_SOFTWARE_ENDSTOPS EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
524
+#define HAS_RESUME_CONTINUE   ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER)
525
+#define HAS_COLOR_LEDS        ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED)
526
+#define HAS_LEDS_OFF_FLAG     (BOTH(PRINTER_EVENT_LEDS, SDSUPPORT) && HAS_RESUME_CONTINUE)
527
+#define HAS_PRINT_PROGRESS    EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY)
536 528
 #define HAS_SERVICE_INTERVALS (SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0)
537
-#define HAS_FILAMENT_SENSOR ENABLED(FILAMENT_RUNOUT_SENSOR)
529
+#define HAS_FILAMENT_SENSOR   ENABLED(FILAMENT_RUNOUT_SENSOR)
538 530
 
539
-#define Z_MULTI_STEPPER_DRIVERS (ENABLED(Z_DUAL_STEPPER_DRIVERS) || ENABLED(Z_TRIPLE_STEPPER_DRIVERS))
540
-#define Z_MULTI_ENDSTOPS (ENABLED(Z_DUAL_ENDSTOPS) || ENABLED(Z_TRIPLE_ENDSTOPS))
541
-#define HAS_EXTRA_ENDSTOPS (ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
531
+#define Z_MULTI_STEPPER_DRIVERS EITHER(Z_DUAL_STEPPER_DRIVERS, Z_TRIPLE_STEPPER_DRIVERS)
532
+#define Z_MULTI_ENDSTOPS EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
533
+#define HAS_EXTRA_ENDSTOPS (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
542 534
 
543
-#define IS_SCARA     (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA))
535
+#define IS_SCARA     EITHER(MORGAN_SCARA, MAKERARM_SCARA)
544 536
 #define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
545 537
 #define IS_CARTESIAN !IS_KINEMATIC
546 538
 

+ 34
- 34
Marlin/src/inc/Conditionals_post.h View File

@@ -106,9 +106,9 @@
106 106
 /**
107 107
  * CoreXY, CoreXZ, and CoreYZ - and their reverse
108 108
  */
109
-#define CORE_IS_XY (ENABLED(COREXY) || ENABLED(COREYX))
110
-#define CORE_IS_XZ (ENABLED(COREXZ) || ENABLED(COREZX))
111
-#define CORE_IS_YZ (ENABLED(COREYZ) || ENABLED(COREZY))
109
+#define CORE_IS_XY EITHER(COREXY, COREYX)
110
+#define CORE_IS_XZ EITHER(COREXZ, COREZX)
111
+#define CORE_IS_YZ EITHER(COREYZ, COREZY)
112 112
 #define IS_CORE (CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ)
113 113
 #if IS_CORE
114 114
   #if CORE_IS_XY
@@ -124,7 +124,7 @@
124 124
     #define CORE_AXIS_1 B_AXIS
125 125
     #define CORE_AXIS_2 C_AXIS
126 126
   #endif
127
-  #if ENABLED(COREYX) || ENABLED(COREZX) || ENABLED(COREZY)
127
+  #if ANY(COREYX, COREZX, COREZY)
128 128
     #define CORESIGN(n) (-(n))
129 129
   #else
130 130
     #define CORESIGN(n) (n)
@@ -426,7 +426,7 @@
426 426
   #define HEATER_CHAMBER_USES_THERMISTOR
427 427
 #endif
428 428
 
429
-#define HOTEND_USES_THERMISTOR (ENABLED(HEATER_0_USES_THERMISTOR) || ENABLED(HEATER_1_USES_THERMISTOR) || ENABLED(HEATER_2_USES_THERMISTOR) || ENABLED(HEATER_3_USES_THERMISTOR) || ENABLED(HEATER_4_USES_THERMISTOR))
429
+#define HOTEND_USES_THERMISTOR ANY(HEATER_0_USES_THERMISTOR, HEATER_1_USES_THERMISTOR, HEATER_2_USES_THERMISTOR, HEATER_3_USES_THERMISTOR, HEATER_4_USES_THERMISTOR)
430 430
 
431 431
 /**
432 432
  * Default hotend offsets, if not defined
@@ -877,8 +877,8 @@
877 877
   #define AXIS_HAS_STALLGUARD(ST)  (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
878 878
   #define AXIS_HAS_STEALTHCHOP(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160))
879 879
 
880
-  #define STEALTHCHOP_ENABLED (ENABLED(STEALTHCHOP_XY) || ENABLED(STEALTHCHOP_Z) || ENABLED(STEALTHCHOP_E))
881
-  #define USE_SENSORLESS (ENABLED(SENSORLESS_HOMING) || ENABLED(SENSORLESS_PROBING))
880
+  #define STEALTHCHOP_ENABLED ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
881
+  #define USE_SENSORLESS EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
882 882
   // Disable Z axis sensorless homing if a probe is used to home the Z axis
883 883
   #if HOMING_Z_WITH_PROBE
884 884
     #undef Z_STALL_SENSITIVITY
@@ -940,8 +940,8 @@
940 940
 #if !HAS_HEATED_BED
941 941
   #undef PIDTEMPBED
942 942
 #endif
943
-#define HAS_PID_HEATING (ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED))
944
-#define HAS_PID_FOR_BOTH (ENABLED(PIDTEMP) && ENABLED(PIDTEMPBED))
943
+#define HAS_PID_HEATING EITHER(PIDTEMP, PIDTEMPBED)
944
+#define HAS_PID_FOR_BOTH BOTH(PIDTEMP, PIDTEMPBED)
945 945
 
946 946
 // Thermal protection
947 947
 #define HAS_THERMALLY_PROTECTED_BED (HAS_HEATED_BED && ENABLED(THERMAL_PROTECTION_BED))
@@ -976,9 +976,9 @@
976 976
   #define Z_PROBE_SERVO_NR -1
977 977
 #endif
978 978
 
979
-#define HAS_SERVO_ANGLES (ENABLED(SWITCHING_EXTRUDER) || ENABLED(SWITCHING_NOZZLE) || (HAS_Z_SERVO_PROBE && defined(Z_PROBE_SERVO_NR)))
979
+#define HAS_SERVO_ANGLES (EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) || (HAS_Z_SERVO_PROBE && defined(Z_PROBE_SERVO_NR)))
980 980
 
981
-#if !HAS_SERVO_ANGLES
981
+#if !HAS_SERVO_ANGLES || ENABLED(BLTOUCH)
982 982
   #undef EDITABLE_SERVO_ANGLES
983 983
 #endif
984 984
 
@@ -986,17 +986,17 @@
986 986
 #define HAS_FILAMENT_WIDTH_SENSOR (PIN_EXISTS(FILWIDTH))
987 987
 
988 988
 // User Interface
989
-#define HAS_HOME (PIN_EXISTS(HOME))
990
-#define HAS_KILL (PIN_EXISTS(KILL))
991
-#define HAS_SUICIDE (PIN_EXISTS(SUICIDE))
992
-#define HAS_PHOTOGRAPH (PIN_EXISTS(PHOTOGRAPH))
993
-#define HAS_BUZZER (PIN_EXISTS(BEEPER) || ENABLED(LCD_USE_I2C_BUZZER))
994
-#define HAS_CASE_LIGHT (PIN_EXISTS(CASE_LIGHT) && ENABLED(CASE_LIGHT_ENABLE))
989
+#define HAS_HOME        (PIN_EXISTS(HOME))
990
+#define HAS_KILL        (PIN_EXISTS(KILL))
991
+#define HAS_SUICIDE     (PIN_EXISTS(SUICIDE))
992
+#define HAS_PHOTOGRAPH  (PIN_EXISTS(PHOTOGRAPH))
993
+#define HAS_BUZZER      (PIN_EXISTS(BEEPER) || ENABLED(LCD_USE_I2C_BUZZER))
994
+#define HAS_CASE_LIGHT  (PIN_EXISTS(CASE_LIGHT) && ENABLED(CASE_LIGHT_ENABLE))
995 995
 
996 996
 // Digital control
997
-#define HAS_STEPPER_RESET (PIN_EXISTS(STEPPER_RESET))
998
-#define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS))
999
-#define HAS_MOTOR_CURRENT_PWM (PIN_EXISTS(MOTOR_CURRENT_PWM_X) || PIN_EXISTS(MOTOR_CURRENT_PWM_Y) || PIN_EXISTS(MOTOR_CURRENT_PWM_XY) || PIN_EXISTS(MOTOR_CURRENT_PWM_Z) || PIN_EXISTS(MOTOR_CURRENT_PWM_E))
997
+#define HAS_STEPPER_RESET     (PIN_EXISTS(STEPPER_RESET))
998
+#define HAS_DIGIPOTSS         (PIN_EXISTS(DIGIPOTSS))
999
+#define HAS_MOTOR_CURRENT_PWM ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E)
1000 1000
 
1001 1001
 #define HAS_MICROSTEPS (HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS)
1002 1002
 
@@ -1055,7 +1055,7 @@
1055 1055
   #undef AUTO_REPORT_TEMPERATURES
1056 1056
 #endif
1057 1057
 
1058
-#define HAS_AUTO_REPORTING (ENABLED(AUTO_REPORT_TEMPERATURES) || ENABLED(AUTO_REPORT_SD_STATUS))
1058
+#define HAS_AUTO_REPORTING EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS)
1059 1059
 
1060 1060
 /**
1061 1061
  * This setting is also used by M109 when trying to calculate
@@ -1272,14 +1272,14 @@
1272 1272
 /**
1273 1273
  * Set granular options based on the specific type of leveling
1274 1274
  */
1275
-#define UBL_SEGMENTED   (ENABLED(AUTO_BED_LEVELING_UBL) && (ENABLED(DELTA)))
1276
-#define ABL_PLANAR      (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT))
1277
-#define ABL_GRID        (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR))
1275
+#define UBL_SEGMENTED   BOTH(AUTO_BED_LEVELING_UBL, DELTA)
1276
+#define ABL_PLANAR      EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT)
1277
+#define ABL_GRID        EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR)
1278 1278
 #define HAS_ABL_NOT_UBL (ABL_PLANAR || ABL_GRID)
1279 1279
 #define HAS_ABL_OR_UBL  (HAS_ABL_NOT_UBL || ENABLED(AUTO_BED_LEVELING_UBL))
1280 1280
 #define HAS_LEVELING    (HAS_ABL_OR_UBL || ENABLED(MESH_BED_LEVELING))
1281 1281
 #define HAS_AUTOLEVEL   (HAS_ABL_OR_UBL && DISABLED(PROBE_MANUALLY))
1282
-#define HAS_MESH        (ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(MESH_BED_LEVELING))
1282
+#define HAS_MESH        ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING)
1283 1283
 #define PLANNER_LEVELING      (HAS_LEVELING && DISABLED(AUTO_BED_LEVELING_UBL))
1284 1284
 #define HAS_PROBING_PROCEDURE (HAS_ABL_OR_UBL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST))
1285 1285
 #define HAS_POSITION_MODIFIERS (ENABLED(FWRETRACT) || HAS_LEVELING || ENABLED(SKEW_CORRECTION))
@@ -1297,8 +1297,8 @@
1297 1297
   #undef NO_FAN_SLOWING_IN_PID_TUNING
1298 1298
 #endif
1299 1299
 
1300
-#define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0))
1301
-#define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF))
1300
+#define QUIET_PROBING (HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0))
1301
+#define HEATER_IDLE_HANDLER EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF)
1302 1302
 
1303 1303
 #if ENABLED(ADVANCED_PAUSE_FEATURE) && !defined(FILAMENT_CHANGE_SLOW_LOAD_LENGTH)
1304 1304
   #define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0
@@ -1400,7 +1400,7 @@
1400 1400
 /**
1401 1401
  * Default mesh area is an area with an inset margin on the print area.
1402 1402
  */
1403
-#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
1403
+#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL)
1404 1404
   #if IS_KINEMATIC
1405 1405
     // Probing points may be verified at compile time within the radius
1406 1406
     // using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!")
@@ -1440,7 +1440,7 @@
1440 1440
 
1441 1441
 #endif // MESH_BED_LEVELING || AUTO_BED_LEVELING_UBL
1442 1442
 
1443
-#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_3POINT)
1443
+#if EITHER(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT)
1444 1444
   #if IS_KINEMATIC
1445 1445
     #define SIN0    0.0
1446 1446
     #define SIN120  0.866025
@@ -1488,7 +1488,7 @@
1488 1488
   #endif
1489 1489
 #endif
1490 1490
 
1491
-#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
1491
+#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR)
1492 1492
   #ifndef LEFT_PROBE_BED_POSITION
1493 1493
     #define LEFT_PROBE_BED_POSITION MIN_PROBE_X
1494 1494
   #endif
@@ -1582,7 +1582,7 @@
1582 1582
 #endif
1583 1583
 
1584 1584
 // Add commands that need sub-codes to this list
1585
-#define USE_GCODE_SUBCODES ENABLED(G38_PROBE_TARGET) || ENABLED(CNC_COORDINATE_SYSTEMS) || ENABLED(POWER_LOSS_RECOVERY)
1585
+#define USE_GCODE_SUBCODES ANY(G38_PROBE_TARGET, CNC_COORDINATE_SYSTEMS, POWER_LOSS_RECOVERY)
1586 1586
 
1587 1587
 // Parking Extruder
1588 1588
 #if ENABLED(PARKING_EXTRUDER)
@@ -1624,8 +1624,8 @@
1624 1624
   #endif
1625 1625
 #endif
1626 1626
 
1627
-// Nozzle park
1628
-#if ENABLED(NOZZLE_PARK_FEATURE) && ENABLED(DELTA)
1627
+// Nozzle park for Delta
1628
+#if BOTH(NOZZLE_PARK_FEATURE, DELTA)
1629 1629
   #undef NOZZLE_PARK_Z_FEEDRATE
1630 1630
   #define NOZZLE_PARK_Z_FEEDRATE NOZZLE_PARK_XY_FEEDRATE
1631 1631
 #endif
@@ -1666,7 +1666,7 @@
1666 1666
 // If platform requires early initialization of watchdog to properly boot
1667 1667
 #define EARLY_WATCHDOG (ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM))
1668 1668
 
1669
-#define USE_EXECUTE_COMMANDS_IMMEDIATE (ENABLED(G29_RETRY_AND_RECOVER) || ENABLED(GCODE_MACROS) || ENABLED(POWER_LOSS_RECOVERY) || HAS_DRIVER(L6470))
1669
+#define USE_EXECUTE_COMMANDS_IMMEDIATE (ANY(G29_RETRY_AND_RECOVER, GCODE_MACROS, POWER_LOSS_RECOVERY) || HAS_DRIVER(L6470))
1670 1670
 
1671 1671
 #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
1672 1672
   #define Z_STEPPER_COUNT 3

+ 41
- 41
Marlin/src/inc/SanityCheck.h View File

@@ -395,7 +395,7 @@
395 395
   #elif TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
396 396
     #error "TX_BUFFER_SIZE must be 0 or a power of 2 between 1 and 256."
397 397
   #endif
398
-#elif ENABLED(SERIAL_XON_XOFF) || ENABLED(SERIAL_STATS_MAX_RX_QUEUED) || ENABLED(SERIAL_STATS_DROPPED_RX)
398
+#elif ANY(SERIAL_XON_XOFF, SERIAL_STATS_MAX_RX_QUEUED, SERIAL_STATS_DROPPED_RX)
399 399
   #error "SERIAL_XON_XOFF and SERIAL_STATS_* features not supported on USB-native AVR devices."
400 400
 #endif
401 401
 
@@ -410,7 +410,7 @@
410 410
 /**
411 411
  * Dual / Triple Stepper Drivers
412 412
  */
413
-#if ENABLED(X_DUAL_STEPPER_DRIVERS) && ENABLED(DUAL_X_CARRIAGE)
413
+#if BOTH(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE)
414 414
   #error "DUAL_X_CARRIAGE is not compatible with X_DUAL_STEPPER_DRIVERS."
415 415
 #elif ENABLED(X_DUAL_STEPPER_DRIVERS) && !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR)
416 416
   #error "X_DUAL_STEPPER_DRIVERS requires X2 pins (and an extra E plug)."
@@ -462,21 +462,21 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
462 462
   #error "PULLDOWN pin mode is not available on the selected board."
463 463
 #endif
464 464
 
465
-#if ENABLED(ENDSTOPPULLUPS) && ENABLED(ENDSTOPPULLDOWNS)
465
+#if BOTH(ENDSTOPPULLUPS, ENDSTOPPULLDOWNS)
466 466
   #error "Enable only one of ENDSTOPPULLUPS or ENDSTOPPULLDOWNS."
467
-#elif ENABLED(FIL_RUNOUT_PULLUP) && ENABLED(FIL_RUNOUT_PULLDOWN)
467
+#elif BOTH(FIL_RUNOUT_PULLUP, FIL_RUNOUT_PULLDOWN)
468 468
   #error "Enable only one of FIL_RUNOUT_PULLUP or FIL_RUNOUT_PULLDOWN."
469
-#elif ENABLED(ENDSTOPPULLUP_XMAX) && ENABLED(ENDSTOPPULLDOWN_XMAX)
469
+#elif BOTH(ENDSTOPPULLUP_XMAX, ENDSTOPPULLDOWN_XMAX)
470 470
   #error "Enable only one of ENDSTOPPULLUP_X_MAX or ENDSTOPPULLDOWN_X_MAX."
471
-#elif ENABLED(ENDSTOPPULLUP_YMAX) && ENABLED(ENDSTOPPULLDOWN_YMAX)
471
+#elif BOTH(ENDSTOPPULLUP_YMAX, ENDSTOPPULLDOWN_YMAX)
472 472
   #error "Enable only one of ENDSTOPPULLUP_Y_MAX or ENDSTOPPULLDOWN_Y_MAX."
473
-#elif ENABLED(ENDSTOPPULLUP_ZMAX) && ENABLED(ENDSTOPPULLDOWN_ZMAX)
473
+#elif BOTH(ENDSTOPPULLUP_ZMAX, ENDSTOPPULLDOWN_ZMAX)
474 474
   #error "Enable only one of ENDSTOPPULLUP_Z_MAX or ENDSTOPPULLDOWN_Z_MAX."
475
-#elif ENABLED(ENDSTOPPULLUP_XMIN) && ENABLED(ENDSTOPPULLDOWN_XMIN)
475
+#elif BOTH(ENDSTOPPULLUP_XMIN, ENDSTOPPULLDOWN_XMIN)
476 476
   #error "Enable only one of ENDSTOPPULLUP_X_MIN or ENDSTOPPULLDOWN_X_MIN."
477
-#elif ENABLED(ENDSTOPPULLUP_YMIN) && ENABLED(ENDSTOPPULLDOWN_YMIN)
477
+#elif BOTH(ENDSTOPPULLUP_YMIN, ENDSTOPPULLDOWN_YMIN)
478 478
   #error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN."
479
-#elif ENABLED(ENDSTOPPULLUP_ZMIN) && ENABLED(ENDSTOPPULLDOWN_ZMIN)
479
+#elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN)
480 480
   #error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN."
481 481
 #endif
482 482
 
@@ -513,7 +513,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
513 513
 /**
514 514
  * Custom Boot and Status screens
515 515
  */
516
-#if DISABLED(DOGLCD) && (ENABLED(SHOW_CUSTOM_BOOTSCREEN) || ENABLED(CUSTOM_STATUS_SCREEN_IMAGE))
516
+#if DISABLED(DOGLCD) && EITHER(SHOW_CUSTOM_BOOTSCREEN, CUSTOM_STATUS_SCREEN_IMAGE)
517 517
   #error "Graphical LCD is required for SHOW_CUSTOM_BOOTSCREEN and CUSTOM_STATUS_SCREEN_IMAGE."
518 518
 #endif
519 519
 
@@ -568,9 +568,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
568 568
 #if ENABLED(BABYSTEPPING)
569 569
   #if ENABLED(SCARA)
570 570
     #error "BABYSTEPPING is not implemented for SCARA yet."
571
-  #elif ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
571
+  #elif BOTH(DELTA, BABYSTEP_XY)
572 572
     #error "BABYSTEPPING only implemented for Z axis on deltabots."
573
-  #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && ENABLED(MESH_BED_LEVELING)
573
+  #elif BOTH(BABYSTEP_ZPROBE_OFFSET, MESH_BED_LEVELING)
574 574
     #error "MESH_BED_LEVELING and BABYSTEP_ZPROBE_OFFSET is not a valid combination"
575 575
   #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && !HAS_BED_PROBE
576 576
     #error "BABYSTEP_ZPROBE_OFFSET requires a probe."
@@ -580,7 +580,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
580 580
     #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a BABYSTEP_ZPROBE_OFFSET."
581 581
   #elif ENABLED(BABYSTEP_HOTEND_Z_OFFSET) && !HAS_HOTEND_OFFSET
582 582
     #error "BABYSTEP_HOTEND_Z_OFFSET requires 2 or more HOTENDS."
583
-  #elif ENABLED(BABYSTEP_ALWAYS_AVAILABLE) && ENABLED(MOVE_Z_WHEN_IDLE)
583
+  #elif BOTH(BABYSTEP_ALWAYS_AVAILABLE, MOVE_Z_WHEN_IDLE)
584 584
     #error "BABYSTEP_ALWAYS_AVAILABLE and MOVE_Z_WHEN_IDLE are incompatible."
585 585
   #endif
586 586
 #endif
@@ -641,7 +641,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
641 641
 /**
642 642
  * Individual axis homing is useless for DELTAS
643 643
  */
644
-#if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) && ENABLED(DELTA)
644
+#if BOTH(INDIVIDUAL_AXIS_HOMING_MENU, DELTA)
645 645
   #error "INDIVIDUAL_AXIS_HOMING_MENU is incompatible with DELTA kinematics."
646 646
 #endif
647 647
 
@@ -810,7 +810,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
810 810
     #error "Enable only one of PARKING_EXTRUDER and MAGNETIC_PARKING_EXTRUDER."
811 811
   #elif EXTRUDERS != 2
812 812
     #error "PARKING_EXTRUDER requires exactly 2 EXTRUDERS."
813
-  #elif !PIN_EXISTS(SOL0) || !PIN_EXISTS(SOL1)
813
+  #elif !PIN_EXISTS(SOL0, SOL1)
814 814
     #error "PARKING_EXTRUDER requires SOL0_PIN and SOL1_PIN."
815 815
   #elif !defined(PARKING_EXTRUDER_PARKING_X)
816 816
     #error "PARKING_EXTRUDER requires PARKING_EXTRUDER_PARKING_X."
@@ -907,7 +907,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
907 907
 /**
908 908
  * Bed Heating Options - PID vs Limit Switching
909 909
  */
910
-#if ENABLED(PIDTEMPBED) && ENABLED(BED_LIMIT_SWITCHING)
910
+#if BOTH(PIDTEMPBED, BED_LIMIT_SWITCHING)
911 911
   #error "To use BED_LIMIT_SWITCHING you must disable PIDTEMPBED."
912 912
 #endif
913 913
 
@@ -974,7 +974,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
974 974
   /**
975 975
    * Z_PROBE_SLED is incompatible with DELTA
976 976
    */
977
-  #if ENABLED(Z_PROBE_SLED) && ENABLED(DELTA)
977
+  #if BOTH(Z_PROBE_SLED, DELTA)
978 978
     #error "You cannot use Z_PROBE_SLED with DELTA."
979 979
   #endif
980 980
 
@@ -1087,7 +1087,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1087 1087
  * Bed Leveling Requirements
1088 1088
  */
1089 1089
 
1090
-#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_3POINT)
1090
+#if EITHER(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT)
1091 1091
   static_assert(WITHIN(PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X), "PROBE_PT_1_X is outside the probe region.");
1092 1092
   static_assert(WITHIN(PROBE_PT_2_X, MIN_PROBE_X, MAX_PROBE_X), "PROBE_PT_2_X is outside the probe region.");
1093 1093
   static_assert(WITHIN(PROBE_PT_3_X, MIN_PROBE_X, MAX_PROBE_X), "PROBE_PT_3_X is outside the probe region.");
@@ -1221,8 +1221,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1221 1221
 /**
1222 1222
  * Make sure DISABLE_[XYZ] compatible with selected homing options
1223 1223
  */
1224
-#if ENABLED(DISABLE_X) || ENABLED(DISABLE_Y) || ENABLED(DISABLE_Z)
1225
-  #if ENABLED(HOME_AFTER_DEACTIVATE) || ENABLED(Z_SAFE_HOMING)
1224
+#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z)
1225
+  #if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING)
1226 1226
     #error "DISABLE_[XYZ] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING."
1227 1227
   #endif
1228 1228
 #endif
@@ -1255,7 +1255,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1255 1255
 #if ENABLED(SAV_3DGLCD)
1256 1256
   #if DISABLED(U8GLIB_SSD1306) && DISABLED(U8GLIB_SH1106)
1257 1257
     #error "Enable a SAV_3DGLCD display type: U8GLIB_SSD1306 or U8GLIB_SH1106."
1258
-  #elif ENABLED(U8GLIB_SSD1306) && ENABLED(U8GLIB_SH1106)
1258
+  #elif BOTH(U8GLIB_SSD1306, U8GLIB_SH1106)
1259 1259
     #error "Only enable one SAV_3DGLCD display type: U8GLIB_SSD1306 or U8GLIB_SH1106."
1260 1260
   #endif
1261 1261
 #endif
@@ -1334,11 +1334,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1334 1334
  */
1335 1335
 #if !HAS_HEATER_0
1336 1336
   #error "HEATER_0_PIN not defined for this board."
1337
-#elif !PIN_EXISTS(TEMP_0) && !PIN_EXISTS(MAX6675_SS)
1337
+#elif !ANY_PIN(TEMP_0, MAX6675_SS)
1338 1338
   #error "TEMP_0_PIN not defined for this board."
1339
-#elif ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PIN_EXISTS(E0_STEP) || !PIN_EXISTS(E0_DIR)))
1339
+#elif ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PIN_EXISTS(E0_STEP, E0_DIR))
1340 1340
   #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board."
1341
-#elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PIN_EXISTS(E0_STEP) || !PIN_EXISTS(E0_DIR) || !HAS_E0_ENABLE))
1341
+#elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PIN_EXISTS(E0_STEP, E0_DIR) || !HAS_E0_ENABLE))
1342 1342
   #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board."
1343 1343
 #elif TEMP_SENSOR_0 == 0
1344 1344
   #error "TEMP_SENSOR_0 is required."
@@ -1356,7 +1356,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1356 1356
     #error "MAX6675_SS2_PIN (required for TEMP_SENSOR_1) not defined for this board."
1357 1357
   #elif TEMP_SENSOR_1 == 0
1358 1358
     #error "TEMP_SENSOR_1 is required with 2 or more HOTENDS."
1359
-  #elif !PIN_EXISTS(TEMP_1) && !PIN_EXISTS(MAX6675_SS2)
1359
+  #elif !ANY_PIN(TEMP_1, MAX6675_SS2)
1360 1360
     #error "TEMP_1_PIN not defined for this board."
1361 1361
   #endif
1362 1362
   #if HOTENDS > 2
@@ -1434,7 +1434,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1434 1434
 /**
1435 1435
  * Temperature status LEDs
1436 1436
  */
1437
-#if ENABLED(TEMP_STAT_LEDS) && !PIN_EXISTS(STAT_LED_RED) && !PIN_EXISTS(STAT_LED_BLUE)
1437
+#if ENABLED(TEMP_STAT_LEDS) && !ANY_PIN(STAT_LED_RED, STAT_LED_BLUE)
1438 1438
   #error "TEMP_STAT_LEDS requires STAT_LED_RED_PIN or STAT_LED_BLUE_PIN, preferably both."
1439 1439
 #endif
1440 1440
 
@@ -1442,7 +1442,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1442 1442
  * LED Control Menu
1443 1443
  */
1444 1444
 #if ENABLED(LED_CONTROL_MENU) && !HAS_COLOR_LEDS
1445
-  #error "LED_CONTROL_MENU requires BLINKM, RGB_LED, RGBW_LED, PCA9632, or NEOPIXEL_LED."
1445
+  #error "LED_CONTROL_MENU requires BLINKM, RGB_LED, RGBW_LED, PCA9533, PCA9632, or NEOPIXEL_LED."
1446 1446
 #endif
1447 1447
 
1448 1448
 /**
@@ -1467,27 +1467,27 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1467 1467
  */
1468 1468
 #if DISABLED(MK2_MULTIPLEXER) // MK2_MULTIPLEXER uses E0 stepper only
1469 1469
   #if E_STEPPERS
1470
-    #if !(PIN_EXISTS(E0_STEP) && PIN_EXISTS(E0_DIR) && HAS_E0_ENABLE)
1470
+    #if !(PIN_EXISTS(E0_STEP, E0_DIR) && HAS_E0_ENABLE)
1471 1471
       #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board."
1472 1472
     #endif
1473 1473
     #if E_STEPPERS > 1
1474
-      #if !(PIN_EXISTS(E1_STEP) && PIN_EXISTS(E1_DIR) && HAS_E1_ENABLE)
1474
+      #if !(PIN_EXISTS(E1_STEP, E1_DIR) && HAS_E1_ENABLE)
1475 1475
         #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board."
1476 1476
       #endif
1477 1477
       #if E_STEPPERS > 2
1478
-        #if !(PIN_EXISTS(E2_STEP) && PIN_EXISTS(E2_DIR) && HAS_E2_ENABLE)
1478
+        #if !(PIN_EXISTS(E2_STEP, E2_DIR) && HAS_E2_ENABLE)
1479 1479
           #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board."
1480 1480
         #endif
1481 1481
         #if E_STEPPERS > 3
1482
-          #if !(PIN_EXISTS(E3_STEP) && PIN_EXISTS(E3_DIR) && HAS_E3_ENABLE)
1482
+          #if !(PIN_EXISTS(E3_STEP, E3_DIR) && HAS_E3_ENABLE)
1483 1483
             #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board."
1484 1484
           #endif
1485 1485
           #if E_STEPPERS > 4
1486
-            #if !(PIN_EXISTS(E4_STEP) && PIN_EXISTS(E4_DIR) && HAS_E4_ENABLE)
1486
+            #if !(PIN_EXISTS(E4_STEP, E4_DIR) && HAS_E4_ENABLE)
1487 1487
               #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
1488 1488
             #endif
1489 1489
             #if E_STEPPERS > 5
1490
-              #if !(PIN_EXISTS(E5_STEP) && PIN_EXISTS(E5_DIR) && HAS_E5_ENABLE)
1490
+              #if !(PIN_EXISTS(E5_STEP, E5_DIR) && HAS_E5_ENABLE)
1491 1491
                 #error "E5_STEP_PIN, E5_DIR_PIN, or E5_ENABLE_PIN not defined for this board."
1492 1492
               #endif
1493 1493
             #endif // E_STEPPERS > 5
@@ -1675,9 +1675,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1675 1675
 /**
1676 1676
  * RGB_LED Requirements
1677 1677
  */
1678
-#define _RGB_TEST (PIN_EXISTS(RGB_LED_R) && PIN_EXISTS(RGB_LED_G) && PIN_EXISTS(RGB_LED_B))
1678
+#define _RGB_TEST (PIN_EXISTS(RGB_LED_R, RGB_LED_G, RGB_LED_B))
1679 1679
 #if ENABLED(PRINTER_EVENT_LEDS) && !HAS_COLOR_LEDS
1680
-  #error "PRINTER_EVENT_LEDS requires BLINKM, PCA9632, RGB_LED, RGBW_LED or NEOPIXEL_LED."
1680
+  #error "PRINTER_EVENT_LEDS requires BLINKM, PCA9533, PCA9632, RGB_LED, RGBW_LED or NEOPIXEL_LED."
1681 1681
 #elif ENABLED(RGB_LED)
1682 1682
   #if !_RGB_TEST
1683 1683
     #error "RGB_LED requires RGB_LED_R_PIN, RGB_LED_G_PIN, and RGB_LED_B_PIN."
@@ -1813,7 +1813,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1813 1813
 /**
1814 1814
  * Check existing RX/TX pins against enable TMC UART drivers.
1815 1815
  */
1816
-#define INVALID_TMC2208(ST) (AXIS_DRIVER_TYPE(ST, TMC2208) && !(defined(ST##_HARDWARE_SERIAL) || (PIN_EXISTS(ST##_SERIAL_RX) && PIN_EXISTS(ST##_SERIAL_TX))))
1816
+#define INVALID_TMC2208(ST) (AXIS_DRIVER_TYPE(ST, TMC2208) && !(defined(ST##_HARDWARE_SERIAL) || (PIN_EXISTS(ST##_SERIAL_RX, ST##_SERIAL_TX))))
1817 1817
 #if INVALID_TMC2208(X)
1818 1818
   #error "TMC2208 on X requires X_HARDWARE_SERIAL or X_SERIAL_(RX|TX)_PIN."
1819 1819
 #elif INVALID_TMC2208(X2)
@@ -1887,7 +1887,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1887 1887
   // is necessary in order to reset the stallGuard indication between the initial movement of all three
1888 1888
   // towers to +Z and the individual homing of each tower. This restriction can be removed once a means of
1889 1889
   // clearing the stallGuard activated status is found.
1890
-  #if ENABLED(DELTA) && !(ENABLED(STEALTHCHOP_XY) && ENABLED(STEALTHCHOP_Z))
1890
+  #if ENABLED(DELTA) && !BOTH(STEALTHCHOP_XY, STEALTHCHOP_Z)
1891 1891
     #error "SENSORLESS_HOMING on DELTA currently requires STEALTHCHOP_XY and STEALTHCHOP_Z."
1892 1892
   #elif X_SENSORLESS && X_HOME_DIR == -1 && (!X_MIN_ENDSTOP_INVERTING || DISABLED(ENDSTOPPULLUP_XMIN))
1893 1893
     #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING and ENDSTOPPULLUP_XMIN when homing to X_MIN."
@@ -1909,7 +1909,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1909 1909
 // Sensorless homing/probing requirements
1910 1910
 #if ENABLED(SENSORLESS_HOMING) && !(X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS)
1911 1911
   #error "SENSORLESS_HOMING requires a TMC stepper driver with StallGuard on X, Y, or Z axes."
1912
-#elif ENABLED(SENSORLESS_PROBING) && ENABLED(DELTA) && !(X_SENSORLESS && Y_SENSORLESS && Z_SENSORLESS)
1912
+#elif BOTH(SENSORLESS_PROBING, DELTA) && !(X_SENSORLESS && Y_SENSORLESS && Z_SENSORLESS)
1913 1913
   #error "SENSORLESS_PROBING for DELTA requires TMC stepper drivers with StallGuard on X, Y, and Z axes."
1914 1914
 #elif ENABLED(SENSORLESS_PROBING) && !Z_SENSORLESS
1915 1915
   #error "SENSORLESS_PROBING requires a TMC stepper driver with StallGuard on Z."
@@ -1981,7 +1981,7 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
1981 1981
 
1982 1982
 #undef _ARR_TEST
1983 1983
 
1984
-#if ENABLED(CNC_COORDINATE_SYSTEMS) && ENABLED(NO_WORKSPACE_OFFSETS)
1984
+#if BOTH(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS)
1985 1985
   #error "CNC_COORDINATE_SYSTEMS is incompatible with NO_WORKSPACE_OFFSETS."
1986 1986
 #endif
1987 1987
 
@@ -2036,7 +2036,7 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2036 2036
   #error "PRINTCOUNTER requires EEPROM_SETTINGS. Please update your Configuration."
2037 2037
 #endif
2038 2038
 
2039
-#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && !(PIN_EXISTS(USB_CS) && PIN_EXISTS(USB_INTR))
2039
+#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && !PIN_EXISTS(USB_CS, USB_INTR)
2040 2040
   #error "USB_CS_PIN and USB_INTR_PIN are required for USB_FLASH_DRIVE_SUPPORT."
2041 2041
 #endif
2042 2042
 

+ 3
- 3
Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp View File

@@ -40,7 +40,7 @@
40 40
 #include "../../module/planner.h"
41 41
 #include "../../module/motion.h"
42 42
 
43
-#if DISABLED(LCD_PROGRESS_BAR) && ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
43
+#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
44 44
   #include "../../feature/filwidth.h"
45 45
   #include "../../gcode/parser.h"
46 46
 #endif
@@ -57,7 +57,7 @@
57 57
 
58 58
   LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_I2C_PIN_EN, LCD_I2C_PIN_RW, LCD_I2C_PIN_RS, LCD_I2C_PIN_D4, LCD_I2C_PIN_D5, LCD_I2C_PIN_D6, LCD_I2C_PIN_D7);
59 59
 
60
-#elif ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)
60
+#elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008)
61 61
 
62 62
   LCD_CLASS lcd(LCD_I2C_ADDRESS
63 63
     #ifdef DETECT_DEVICE
@@ -628,7 +628,7 @@ void MarlinUI::draw_status_message(const bool blink) {
628 628
       if (progress > 2) return draw_progress_bar(progress);
629 629
     }
630 630
 
631
-  #elif ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
631
+  #elif BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
632 632
 
633 633
     // Alternate Status message and Filament display
634 634
     if (ELAPSED(millis(), next_filament_display)) {

+ 1
- 1
Marlin/src/lcd/dogm/status_screen_DOGM.cpp View File

@@ -572,7 +572,7 @@ void MarlinUI::draw_status_screen() {
572 572
   if (PAGE_CONTAINS(STATUS_BASELINE - INFO_FONT_ASCENT, STATUS_BASELINE + INFO_FONT_DESCENT)) {
573 573
     lcd_moveto(0, STATUS_BASELINE);
574 574
 
575
-    #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
575
+    #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
576 576
       // Alternate Status message and Filament display
577 577
       if (ELAPSED(millis(), next_filament_display)) {
578 578
         lcd_put_u8str_P(PSTR(LCD_STR_FILAM_DIA));

+ 1
- 1
Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp View File

@@ -862,7 +862,7 @@ void ST7920_Lite_Status_Screen::update_status_or_position(bool forceUpdate) {
862 862
 }
863 863
 
864 864
 void ST7920_Lite_Status_Screen::update_progress(const bool forceUpdate) {
865
-  #if ENABLED(LCD_SET_PROGRESS_MANUALLY) || ENABLED(SDSUPPORT)
865
+  #if EITHER(LCD_SET_PROGRESS_MANUALLY, SDSUPPORT)
866 866
 
867 867
     // Since the progress bar involves writing
868 868
     // quite a few bytes to GDRAM, only do this

+ 2
- 2
Marlin/src/lcd/dogm/ultralcd_DOGM.cpp View File

@@ -189,7 +189,7 @@ void MarlinUI::init_lcd() {
189 189
     OUT_WRITE(LCD_BACKLIGHT_PIN, HIGH);
190 190
   #endif
191 191
 
192
-  #if ENABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306)
192
+  #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306)
193 193
     SET_OUTPUT(LCD_PINS_DC);
194 194
     #if !defined(LCD_RESET_PIN)
195 195
       #define LCD_RESET_PIN LCD_PINS_RS
@@ -497,7 +497,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
497 497
 
498 498
   #endif // AUTO_BED_LEVELING_UBL
499 499
 
500
-  #if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) || ENABLED(MESH_EDIT_GFX_OVERLAY)
500
+  #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY)
501 501
 
502 502
     const unsigned char cw_bmp[] PROGMEM = {
503 503
       B00000011,B11111000,B00000000,

+ 2
- 2
Marlin/src/lcd/extensible_ui/ui_api.cpp View File

@@ -59,7 +59,7 @@
59 59
   #include "../../core/utility.h"
60 60
 #endif
61 61
 
62
-#if DO_SWITCH_EXTRUDER || ENABLED(SWITCHING_NOZZLE) || ENABLED(PARKING_EXTRUDER)
62
+#if DO_SWITCH_EXTRUDER || EITHER(SWITCHING_NOZZLE, PARKING_EXTRUDER)
63 63
   #include "../../module/tool_change.h"
64 64
 #endif
65 65
 
@@ -297,7 +297,7 @@ namespace ExtUI {
297 297
   void setActiveTool(const extruder_t extruder, bool no_move) {
298 298
     #if EXTRUDERS > 1
299 299
       const uint8_t e = extruder - E0;
300
-      #if DO_SWITCH_EXTRUDER || ENABLED(SWITCHING_NOZZLE) || ENABLED(PARKING_EXTRUDER)
300
+      #if DO_SWITCH_EXTRUDER || EITHER(SWITCHING_NOZZLE, PARKING_EXTRUDER)
301 301
         if (e != active_extruder)
302 302
           tool_change(e, 0, no_move);
303 303
       #endif

+ 3
- 3
Marlin/src/lcd/menu/menu.cpp View File

@@ -45,7 +45,7 @@
45 45
   #include "../../module/probe.h"
46 46
 #endif
47 47
 
48
-#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) || ENABLED(AUTO_BED_LEVELING_UBL)
48
+#if EITHER(ENABLE_LEVELING_FADE_HEIGHT, AUTO_BED_LEVELING_UBL)
49 49
   #include "../../feature/bedlevel/bedlevel.h"
50 50
 #endif
51 51
 
@@ -205,7 +205,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint32_t encoder/*=0*/) {
205 205
       lcd_z_fade_height = planner.z_fade_height;
206 206
     #endif
207 207
 
208
-    #if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING) && ENABLED(BABYSTEPPING)
208
+    #if BOTH(DOUBLECLICK_FOR_Z_BABYSTEPPING, BABYSTEPPING)
209 209
       static millis_t doubleclick_expire_ms = 0;
210 210
       // Going to menu_main from status screen? Remember first click time.
211 211
       // Going back to status screen within a very short time? Go to Z babystepping.
@@ -405,7 +405,7 @@ void MarlinUI::completion_feedback(const bool good/*=true*/) {
405 405
 
406 406
 #endif // BABYSTEP_ZPROBE_OFFSET
407 407
 
408
-#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(PID_AUTOTUNE_MENU) || ENABLED(ADVANCED_PAUSE_FEATURE)
408
+#if ANY(AUTO_BED_LEVELING_UBL, PID_AUTOTUNE_MENU, ADVANCED_PAUSE_FEATURE)
409 409
 
410 410
   void lcd_enqueue_command(const char * const cmd) {
411 411
     no_reentry = true;

+ 3
- 3
Marlin/src/lcd/menu/menu.h View File

@@ -82,7 +82,7 @@ FORCE_INLINE void draw_menu_item_edit_P(const bool sel, const uint8_t row, PGM_P
82 82
   FORCE_INLINE void draw_menu_item_sdfolder(const bool sel, const uint8_t row, PGM_P const pstr, CardReader &theCard) { draw_sd_menu_item(sel, row, pstr, theCard, true); }
83 83
 #endif
84 84
 
85
-#if HAS_GRAPHICAL_LCD && (ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) || ENABLED(MESH_EDIT_GFX_OVERLAY))
85
+#if HAS_GRAPHICAL_LCD && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY)
86 86
   void _lcd_zoffset_overlay_gfx(const float zvalue);
87 87
 #endif
88 88
 
@@ -340,13 +340,13 @@ void menu_move();
340 340
 void lcd_move_z();
341 341
 void _lcd_draw_homing();
342 342
 
343
-#define HAS_LINE_TO_Z (ENABLED(DELTA) || ENABLED(PROBE_MANUALLY) || ENABLED(MESH_BED_LEVELING) || ENABLED(LEVEL_BED_CORNERS))
343
+#define HAS_LINE_TO_Z ANY(DELTA, PROBE_MANUALLY, MESH_BED_LEVELING, LEVEL_BED_CORNERS)
344 344
 
345 345
 #if HAS_LINE_TO_Z
346 346
   void line_to_z(const float &z);
347 347
 #endif
348 348
 
349
-#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(PID_AUTOTUNE_MENU) || ENABLED(ADVANCED_PAUSE_FEATURE)
349
+#if ANY(AUTO_BED_LEVELING_UBL, PID_AUTOTUNE_MENU, ADVANCED_PAUSE_FEATURE)
350 350
   void lcd_enqueue_command(const char * const cmd);
351 351
   void lcd_enqueue_commands_P(PGM_P const cmd);
352 352
 #endif

+ 1
- 1
Marlin/src/lcd/menu/menu_advanced.cpp View File

@@ -321,7 +321,7 @@ void menu_tmc();
321 321
   #endif // PID_PARAMS_PER_HOTEND
322 322
 #endif // HOTENDS
323 323
 
324
-#define SHOW_MENU_ADVANCED_TEMPERATURE ((ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND) || ENABLED(PID_AUTOTUNE_MENU) || ENABLED(PID_EDIT_MENU))
324
+#define SHOW_MENU_ADVANCED_TEMPERATURE ((ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND) || EITHER(PID_AUTOTUNE_MENU, PID_EDIT_MENU))
325 325
 
326 326
 //
327 327
 // Advanced Settings > Temperature

+ 2
- 2
Marlin/src/lcd/menu/menu_bed_leveling.cpp View File

@@ -36,7 +36,7 @@
36 36
   #include "../../module/probe.h"
37 37
 #endif
38 38
 
39
-#if ENABLED(PROBE_MANUALLY) || ENABLED(MESH_BED_LEVELING)
39
+#if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)
40 40
 
41 41
   #include "../../module/motion.h"
42 42
   #include "../../gcode/queue.h"
@@ -244,7 +244,7 @@ void menu_bed_leveling() {
244 244
   #endif
245 245
 
246 246
   // Level Bed
247
-  #if ENABLED(PROBE_MANUALLY) || ENABLED(MESH_BED_LEVELING)
247
+  #if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)
248 248
     // Manual leveling uses a guided procedure
249 249
     MENU_ITEM(submenu, MSG_LEVEL_BED, _lcd_level_bed_continue);
250 250
   #else

+ 1
- 1
Marlin/src/lcd/menu/menu_configuration.cpp View File

@@ -275,7 +275,7 @@ void menu_configuration() {
275 275
     //
276 276
     // Delta Calibration
277 277
     //
278
-    #if ENABLED(DELTA_CALIBRATION_MENU) || ENABLED(DELTA_AUTO_CALIBRATION)
278
+    #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION)
279 279
       MENU_ITEM(submenu, MSG_DELTA_CALIBRATE, menu_delta_calibrate);
280 280
     #endif
281 281
 

+ 1
- 1
Marlin/src/lcd/menu/menu_delta_calibrate.cpp View File

@@ -26,7 +26,7 @@
26 26
 
27 27
 #include "../../inc/MarlinConfigPre.h"
28 28
 
29
-#if HAS_LCD_MENU && (ENABLED(DELTA_CALIBRATION_MENU) || ENABLED(DELTA_AUTO_CALIBRATION))
29
+#if HAS_LCD_MENU && EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION)
30 30
 
31 31
 #include "menu.h"
32 32
 #include "../../module/delta.h"

+ 1
- 1
Marlin/src/lcd/menu/menu_led.cpp View File

@@ -58,7 +58,7 @@ void menu_led_custom() {
58 58
   MENU_ITEM_EDIT_CALLBACK(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true);
59 59
   MENU_ITEM_EDIT_CALLBACK(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true);
60 60
   MENU_ITEM_EDIT_CALLBACK(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true);
61
-  #if ENABLED(RGBW_LED) || ENABLED(NEOPIXEL_LED)
61
+  #if EITHER(RGBW_LED, NEOPIXEL_LED)
62 62
     MENU_ITEM_EDIT_CALLBACK(uint8, MSG_INTENSITY_W, &leds.color.w, 0, 255, leds.update, true);
63 63
     #if ENABLED(NEOPIXEL_LED)
64 64
       MENU_ITEM_EDIT_CALLBACK(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true);

+ 2
- 2
Marlin/src/lcd/menu/menu_main.cpp View File

@@ -46,8 +46,8 @@
46 46
   #include "../../feature/host_actions.h"
47 47
 #endif
48 48
 
49
-#define MACHINE_CAN_STOP (ENABLED(SDSUPPORT) || ENABLED(HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL))
50
-#define MACHINE_CAN_PAUSE (ENABLED(SDSUPPORT) || ENABLED(HOST_PROMPT_SUPPORT) || ENABLED(PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE))
49
+#define MACHINE_CAN_STOP (EITHER(SDSUPPORT, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL))
50
+#define MACHINE_CAN_PAUSE (ANY(SDSUPPORT, HOST_PROMPT_SUPPORT, PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE))
51 51
 
52 52
 #if MACHINE_CAN_PAUSE
53 53
 

+ 2
- 2
Marlin/src/lcd/menu/menu_motion.cpp View File

@@ -335,7 +335,7 @@ void menu_move() {
335 335
   else
336 336
     MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
337 337
 
338
-  #if ENABLED(SWITCHING_EXTRUDER) || ENABLED(SWITCHING_NOZZLE)
338
+  #if EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE)
339 339
 
340 340
     #if EXTRUDERS == 6
341 341
       switch (active_extruder) {
@@ -376,7 +376,7 @@ void menu_move() {
376 376
 
377 377
   #endif
378 378
 
379
-  #if ENABLED(SWITCHING_EXTRUDER) || ENABLED(SWITCHING_NOZZLE)
379
+  #if EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE)
380 380
 
381 381
     // Only the current...
382 382
     MENU_ITEM(submenu, MSG_MOVE_E, lcd_move_get_e_amount);

+ 1
- 1
Marlin/src/lcd/menu/menu_tune.cpp View File

@@ -107,7 +107,7 @@ void menu_tune() {
107 107
   //
108 108
   // Manual bed leveling, Bed Z:
109 109
   //
110
-  #if ENABLED(MESH_BED_LEVELING) && ENABLED(LCD_BED_LEVELING)
110
+  #if BOTH(MESH_BED_LEVELING, LCD_BED_LEVELING)
111 111
     MENU_ITEM_EDIT(float43, MSG_BED_Z, &mbl.z_offset, -1, 1);
112 112
   #endif
113 113
 

+ 8
- 8
Marlin/src/lcd/ultralcd.cpp View File

@@ -23,7 +23,7 @@
23 23
 #include "../inc/MarlinConfigPre.h"
24 24
 
25 25
 // These displays all share the MarlinUI class
26
-#if HAS_SPI_LCD || ENABLED(MALYAN_LCD) || ENABLED(EXTENSIBLE_UI)
26
+#if HAS_SPI_LCD || EITHER(MALYAN_LCD, EXTENSIBLE_UI)
27 27
   #include "ultralcd.h"
28 28
   MarlinUI ui;
29 29
   #include "../sd/cardreader.h"
@@ -106,7 +106,7 @@
106 106
 
107 107
 uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed
108 108
 
109
-#if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
109
+#if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
110 110
   millis_t MarlinUI::next_filament_display; // = 0
111 111
 #endif
112 112
 
@@ -181,7 +181,7 @@ millis_t next_button_update_ms;
181 181
     return click;
182 182
   }
183 183
 
184
-  #if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(G26_MESH_VALIDATION)
184
+  #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION)
185 185
 
186 186
     bool MarlinUI::external_control; // = false
187 187
 
@@ -449,7 +449,7 @@ void MarlinUI::status_screen() {
449 449
   #if HAS_LCD_MENU
450 450
 
451 451
     if (use_click()) {
452
-      #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
452
+      #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
453 453
         next_filament_display = millis() + 5000UL;  // Show status message for 5s
454 454
       #endif
455 455
       goto_screen(menu_main);
@@ -638,7 +638,7 @@ LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW;
638 638
 
639 639
 bool MarlinUI::detected() {
640 640
   return
641
-    #if (ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)) && defined(DETECT_DEVICE)
641
+    #if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && defined(DETECT_DEVICE)
642 642
       lcd.LcdDetected() == 1
643 643
     #else
644 644
       true
@@ -1008,7 +1008,7 @@ void MarlinUI::update() {
1008 1008
 
1009 1009
       #if HAS_DIGITAL_BUTTONS
1010 1010
 
1011
-        #if BUTTON_EXISTS(EN1) || BUTTON_EXISTS(EN2) || BUTTON_EXISTS(ENC) || BUTTON_EXISTS(BACK)
1011
+        #if ANY_BUTTON(EN1, EN2, ENC, BACK)
1012 1012
 
1013 1013
           uint8_t newbutton = 0;
1014 1014
 
@@ -1034,7 +1034,7 @@ void MarlinUI::update() {
1034 1034
         //
1035 1035
         // Directional buttons
1036 1036
         //
1037
-        #if BUTTON_EXISTS(UP) || BUTTON_EXISTS(DWN) || BUTTON_EXISTS(LFT) || BUTTON_EXISTS(RT)
1037
+        #if ANY_BUTTON(UP, DWN, LFT, RT)
1038 1038
 
1039 1039
           const int8_t pulses = (ENCODER_PULSES_PER_STEP) * encoderDirection;
1040 1040
 
@@ -1175,7 +1175,7 @@ void MarlinUI::update() {
1175 1175
       #endif
1176 1176
     #endif
1177 1177
 
1178
-    #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
1178
+    #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
1179 1179
       next_filament_display = millis() + 5000UL; // Show status message for 5s
1180 1180
     #endif
1181 1181
 

+ 9
- 14
Marlin/src/lcd/ultralcd.h View File

@@ -27,18 +27,13 @@
27 27
   #include "../libs/buzzer.h"
28 28
 #endif
29 29
 
30
-#define HAS_DIGITAL_BUTTONS (!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)        \
31
-                            || (BUTTON_EXISTS(EN1) && BUTTON_EXISTS(EN2)) \
32
-                            || BUTTON_EXISTS(ENC) || BUTTON_EXISTS(BACK)  \
33
-                            || BUTTON_EXISTS(UP)  || BUTTON_EXISTS(DWN)   \
34
-                            || BUTTON_EXISTS(LFT) || BUTTON_EXISTS(RT))
35
-
30
+#define HAS_DIGITAL_BUTTONS (!HAS_ADC_BUTTONS && ENABLED(NEWPANEL) || BUTTON_EXISTS(EN1, EN2) || ANY_BUTTON(ENC, BACK, UP, DWN, LFT, RT))
36 31
 #define HAS_SHIFT_ENCODER   (!HAS_ADC_BUTTONS && (ENABLED(REPRAPWORLD_KEYPAD) || (HAS_SPI_LCD && DISABLED(NEWPANEL))))
37
-#define HAS_ENCODER_WHEEL  ((!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || (BUTTON_EXISTS(EN1) && BUTTON_EXISTS(EN2)) )
32
+#define HAS_ENCODER_WHEEL  ((!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || BUTTON_EXISTS(EN1, EN2))
38 33
 #define HAS_ENCODER_ACTION (HAS_LCD_MENU || ENABLED(ULTIPANEL_FEEDMULTIPLY))
39 34
 
40 35
 // I2C buttons must be read in the main thread
41
-#define HAS_SLOW_BUTTONS (ENABLED(LCD_I2C_VIKI) || ENABLED(LCD_I2C_PANELOLU2))
36
+#define HAS_SLOW_BUTTONS EITHER(LCD_I2C_VIKI, LCD_I2C_PANELOLU2)
42 37
 
43 38
 #if HAS_SPI_LCD
44 39
 
@@ -188,7 +183,7 @@
188 183
 #else
189 184
 
190 185
   #undef BUTTON_EXISTS
191
-  #define BUTTON_EXISTS(BN) false
186
+  #define BUTTON_EXISTS(...) false
192 187
 
193 188
   // Shift register bits correspond to buttons:
194 189
   #define BL_LE 7   // Left
@@ -267,7 +262,7 @@ public:
267 262
   static void clear_lcd();
268 263
   static void init_lcd();
269 264
 
270
-  #if HAS_SPI_LCD || ENABLED(MALYAN_LCD) || ENABLED(EXTENSIBLE_UI)
265
+  #if HAS_SPI_LCD || EITHER(MALYAN_LCD, EXTENSIBLE_UI)
271 266
     static void init();
272 267
     static void update();
273 268
     static void set_alert_status_P(PGM_P message);
@@ -343,7 +338,7 @@ public:
343 338
         static inline void refresh_contrast() { set_contrast(contrast); }
344 339
       #endif
345 340
 
346
-      #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
341
+      #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
347 342
         static millis_t next_filament_display;
348 343
       #endif
349 344
 
@@ -466,13 +461,13 @@ public:
466 461
 
467 462
   #endif
468 463
 
469
-  #if ENABLED(LCD_BED_LEVELING) && (ENABLED(PROBE_MANUALLY) || ENABLED(MESH_BED_LEVELING))
464
+  #if ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)
470 465
     static bool wait_for_bl_move;
471 466
   #else
472 467
     static constexpr bool wait_for_bl_move = false;
473 468
   #endif
474 469
 
475
-  #if HAS_LCD_MENU && (ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(G26_MESH_VALIDATION))
470
+  #if HAS_LCD_MENU && EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION)
476 471
     static bool external_control;
477 472
     FORCE_INLINE static void capture() { external_control = true; }
478 473
     FORCE_INLINE static void release() { external_control = false; }
@@ -493,7 +488,7 @@ public:
493 488
     #endif
494 489
     static void update_buttons();
495 490
     static inline bool button_pressed() { return BUTTON_CLICK(); }
496
-    #if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(G26_MESH_VALIDATION)
491
+    #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION)
497 492
       static void wait_for_release();
498 493
     #endif
499 494
 

+ 1
- 1
Marlin/src/libs/hex_print_routines.cpp View File

@@ -23,7 +23,7 @@
23 23
 #include "../inc/MarlinConfig.h"
24 24
 #include "../gcode/parser.h"
25 25
 
26
-#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(M100_FREE_MEMORY_WATCHER) || ENABLED(DEBUG_GCODE_PARSER) || ENABLED(TMC_DEBUG)
26
+#if ANY(AUTO_BED_LEVELING_UBL, M100_FREE_MEMORY_WATCHER, DEBUG_GCODE_PARSER, TMC_DEBUG)
27 27
 
28 28
   #include "hex_print_routines.h"
29 29
 

+ 1
- 1
Marlin/src/libs/least_squares_fit.cpp View File

@@ -34,7 +34,7 @@
34 34
 
35 35
 #include "../inc/MarlinConfig.h"
36 36
 
37
-#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_LINEAR)
37
+#if EITHER(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_LINEAR)
38 38
 
39 39
 #include "least_squares_fit.h"
40 40
 

+ 1
- 1
Marlin/src/libs/nozzle.cpp View File

@@ -22,7 +22,7 @@
22 22
 
23 23
 #include "../inc/MarlinConfig.h"
24 24
 
25
-#if ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE)
25
+#if EITHER(NOZZLE_CLEAN_FEATURE, NOZZLE_PARK_FEATURE)
26 26
 
27 27
 #include "nozzle.h"
28 28
 

+ 11
- 11
Marlin/src/module/configuration_store.cpp View File

@@ -56,7 +56,7 @@
56 56
 #include "../gcode/gcode.h"
57 57
 #include "../Marlin.h"
58 58
 
59
-#if ENABLED(EEPROM_SETTINGS) || ENABLED(SD_FIRMWARE_UPDATE)
59
+#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE)
60 60
   #include "../HAL/shared/persistent_store_api.h"
61 61
 #endif
62 62
 
@@ -194,7 +194,7 @@ typedef struct SettingsDataStruct {
194 194
           delta_segments_per_second,                    // M665 S
195 195
           delta_calibration_radius,                     // M665 B
196 196
           delta_tower_angle_trim[ABC];                  // M665 XYZ
197
-  #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
197
+  #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
198 198
     float x2_endstop_adj,                               // M666 X
199 199
           y2_endstop_adj,                               // M666 Y
200 200
           z2_endstop_adj,                               // M666 Z (S2)
@@ -340,7 +340,7 @@ void MarlinSettings::postprocess() {
340 340
     fwretract.refresh_autoretract();
341 341
   #endif
342 342
 
343
-  #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
343
+  #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
344 344
     planner.recalculate_max_e_jerk();
345 345
   #endif
346 346
 
@@ -448,7 +448,7 @@ void MarlinSettings::postprocess() {
448 448
 
449 449
       #if HAS_CLASSIC_JERK
450 450
         EEPROM_WRITE(planner.max_jerk);
451
-        #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
451
+        #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
452 452
           dummy = float(DEFAULT_EJERK);
453 453
           EEPROM_WRITE(dummy);
454 454
         #endif
@@ -624,7 +624,7 @@ void MarlinSettings::postprocess() {
624 624
         EEPROM_WRITE(delta_calibration_radius);  // 1 float
625 625
         EEPROM_WRITE(delta_tower_angle_trim);    // 3 floats
626 626
 
627
-      #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
627
+      #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
628 628
 
629 629
         _FIELD_TEST(x2_endstop_adj);
630 630
 
@@ -757,7 +757,7 @@ void MarlinSettings::postprocess() {
757 757
         const fwretract_settings_t autoretract_defaults = { 3, 45, 0, 0, 0, 13, 0, 8 };
758 758
         EEPROM_WRITE(autoretract_defaults);
759 759
       #endif
760
-      #if ENABLED(FWRETRACT) && ENABLED(FWRETRACT_AUTORETRACT)
760
+      #if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT)
761 761
         EEPROM_WRITE(fwretract.autoretract_enabled);
762 762
       #else
763 763
         const bool autoretract_enabled = false;
@@ -1167,7 +1167,7 @@ void MarlinSettings::postprocess() {
1167 1167
 
1168 1168
         #if HAS_CLASSIC_JERK
1169 1169
           EEPROM_READ(planner.max_jerk);
1170
-          #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
1170
+          #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
1171 1171
             EEPROM_READ(dummy);
1172 1172
           #endif
1173 1173
         #else
@@ -1340,7 +1340,7 @@ void MarlinSettings::postprocess() {
1340 1340
           EEPROM_READ(delta_calibration_radius);  // 1 float
1341 1341
           EEPROM_READ(delta_tower_angle_trim);    // 3 floats
1342 1342
 
1343
-        #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
1343
+        #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
1344 1344
 
1345 1345
           _FIELD_TEST(x2_endstop_adj);
1346 1346
 
@@ -1472,7 +1472,7 @@ void MarlinSettings::postprocess() {
1472 1472
           fwretract_settings_t fwretract_settings;
1473 1473
           EEPROM_READ(fwretract_settings);
1474 1474
         #endif
1475
-        #if ENABLED(FWRETRACT) && ENABLED(FWRETRACT_AUTORETRACT)
1475
+        #if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT)
1476 1476
           EEPROM_READ(fwretract.autoretract_enabled);
1477 1477
         #else
1478 1478
           bool autoretract_enabled;
@@ -2066,7 +2066,7 @@ void MarlinSettings::reset() {
2066 2066
     delta_calibration_radius = DELTA_CALIBRATION_RADIUS;
2067 2067
     COPY(delta_tower_angle_trim, dta);
2068 2068
 
2069
-  #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
2069
+  #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
2070 2070
 
2071 2071
     #if ENABLED(X_DUAL_ENDSTOPS)
2072 2072
       endstops.x2_endstop_adj = (
@@ -2623,7 +2623,7 @@ void MarlinSettings::reset() {
2623 2623
         , " Z", LINEAR_UNIT(delta_tower_angle_trim[C_AXIS])
2624 2624
       );
2625 2625
 
2626
-    #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
2626
+    #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
2627 2627
 
2628 2628
       CONFIG_ECHO_HEADING("Endstop adjustment:");
2629 2629
       CONFIG_ECHO_START();

+ 2
- 2
Marlin/src/module/endstops.cpp View File

@@ -36,7 +36,7 @@
36 36
   #include HAL_PATH(../HAL, endstop_interrupts.h)
37 37
 #endif
38 38
 
39
-#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) && ENABLED(SDSUPPORT)
39
+#if BOTH(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED, SDSUPPORT)
40 40
   #include "printcounter.h" // for print_job_timer
41 41
 #endif
42 42
 
@@ -361,7 +361,7 @@ void Endstops::event_handler() {
361 361
       ui.status_printf_P(0, PSTR(MSG_LCD_ENDSTOPS " %c %c %c %c"), chrX, chrY, chrZ, chrP);
362 362
     #endif
363 363
 
364
-    #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) && ENABLED(SDSUPPORT)
364
+    #if BOTH(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED, SDSUPPORT)
365 365
       if (planner.abort_on_endstop_hit) {
366 366
         card.stopSDPrint();
367 367
         quickstop_stepper();

+ 3
- 3
Marlin/src/module/motion.cpp View File

@@ -47,7 +47,7 @@
47 47
   #include "../feature/bedlevel/bedlevel.h"
48 48
 #endif
49 49
 
50
-#if ENABLED(ULTRA_LCD) || ENABLED(EXTENSIBLE_UI)
50
+#if EITHER(ULTRA_LCD, EXTENSIBLE_UI)
51 51
   #include "../lcd/ultralcd.h"
52 52
 #endif
53 53
 
@@ -964,7 +964,7 @@ void clean_up_after_endstop_or_probe_move() {
964 964
 void prepare_move_to_destination() {
965 965
   apply_motion_limits(destination);
966 966
 
967
-  #if ENABLED(PREVENT_COLD_EXTRUSION) || ENABLED(PREVENT_LENGTHY_EXTRUDE)
967
+  #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE)
968 968
 
969 969
     if (!DEBUGGING(DRYRUN)) {
970 970
       if (destination[E_AXIS] != current_position[E_AXIS]) {
@@ -1025,7 +1025,7 @@ bool axis_unhomed_error(const bool x/*=true*/, const bool y/*=true*/, const bool
1025 1025
     if (zz) SERIAL_CHAR('Z');
1026 1026
     SERIAL_ECHOLNPGM(" " MSG_FIRST);
1027 1027
 
1028
-    #if ENABLED(ULTRA_LCD) || ENABLED(EXTENSIBLE_UI)
1028
+    #if EITHER(ULTRA_LCD, EXTENSIBLE_UI)
1029 1029
       ui.status_printf_P(0, PSTR(MSG_HOME " %s%s%s " MSG_FIRST), xx ? MSG_X : "", yy ? MSG_Y : "", zz ? MSG_Z : "");
1030 1030
     #endif
1031 1031
     return true;

+ 7
- 7
Marlin/src/module/planner.cpp View File

@@ -128,7 +128,7 @@ float Planner::steps_to_mm[XYZE_N];           // (mm) Millimeters per step
128 128
   #endif
129 129
 #endif
130 130
 #if HAS_CLASSIC_JERK
131
-  #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
131
+  #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
132 132
     float Planner::max_jerk[XYZ];             // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration.
133 133
   #else
134 134
     float Planner::max_jerk[XYZE];            // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration.
@@ -1751,7 +1751,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1751 1751
     SERIAL_ECHOLNPGM(" steps)");
1752 1752
   //*/
1753 1753
 
1754
-  #if ENABLED(PREVENT_COLD_EXTRUSION) || ENABLED(PREVENT_LENGTHY_EXTRUDE)
1754
+  #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE)
1755 1755
     if (de) {
1756 1756
       #if ENABLED(PREVENT_COLD_EXTRUSION)
1757 1757
         if (thermalManager.tooColdToExtrude(extruder)) {
@@ -2104,7 +2104,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2104 2104
   const uint8_t moves_queued = nonbusy_movesplanned();
2105 2105
 
2106 2106
   // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill
2107
-  #if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT)
2107
+  #if EITHER(SLOWDOWN, ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT)
2108 2108
     // Segment time im micro seconds
2109 2109
     uint32_t segment_time_us = LROUND(1000000.0f / inverse_secs);
2110 2110
   #endif
@@ -2172,7 +2172,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2172 2172
   // Calculate and limit speed in mm/sec for each axis
2173 2173
   float current_speed[NUM_AXIS], speed_factor = 1.0f; // factor <1 decreases speed
2174 2174
   LOOP_XYZE(i) {
2175
-    #if ENABLED(MIXING_EXTRUDER) && ENABLED(RETRACT_SYNC_MIXING)
2175
+    #if BOTH(MIXING_EXTRUDER, RETRACT_SYNC_MIXING)
2176 2176
       // In worst case, only one extruder running, no change is needed.
2177 2177
       // In best case, all extruders run the same amount, we can divide by MIXING_STEPPERS
2178 2178
       float delta_mm_i = 0;
@@ -2485,7 +2485,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2485 2485
     float safe_speed = nominal_speed;
2486 2486
 
2487 2487
     uint8_t limited = 0;
2488
-    #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
2488
+    #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
2489 2489
       LOOP_XYZ(i)
2490 2490
     #else
2491 2491
       LOOP_XYZE(i)
@@ -2522,7 +2522,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2522 2522
 
2523 2523
       // Now limit the jerk in all axes.
2524 2524
       const float smaller_speed_factor = vmax_junction / previous_nominal_speed;
2525
-      #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
2525
+      #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
2526 2526
         LOOP_XYZ(axis)
2527 2527
       #else
2528 2528
         LOOP_XYZE(axis)
@@ -2893,7 +2893,7 @@ void Planner::reset_acceleration_rates() {
2893 2893
     if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
2894 2894
   }
2895 2895
   cutoff_long = 4294967295UL / highest_rate; // 0xFFFFFFFFUL
2896
-  #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
2896
+  #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
2897 2897
     recalculate_max_e_jerk();
2898 2898
   #endif
2899 2899
 }

+ 3
- 3
Marlin/src/module/planner.h View File

@@ -159,7 +159,7 @@ typedef struct block_t {
159 159
 
160 160
 } block_t;
161 161
 
162
-#define HAS_POSITION_FLOAT (ENABLED(LIN_ADVANCE) || ENABLED(SCARA_FEEDRATE_SCALING) || ENABLED(GRADIENT_MIX))
162
+#define HAS_POSITION_FLOAT ANY(LIN_ADVANCE, SCARA_FEEDRATE_SCALING, GRADIENT_MIX)
163 163
 
164 164
 #define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1))
165 165
 
@@ -253,7 +253,7 @@ class Planner {
253 253
 
254 254
     #if HAS_CLASSIC_JERK
255 255
       static float max_jerk[
256
-        #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
256
+        #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
257 257
           XYZ                                    // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration.
258 258
         #else
259 259
           XYZE                                   // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration.
@@ -861,7 +861,7 @@ class Planner {
861 861
       static void autotemp_M104_M109();
862 862
     #endif
863 863
 
864
-    #if ENABLED(JUNCTION_DEVIATION) && ENABLED(LIN_ADVANCE)
864
+    #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE)
865 865
       FORCE_INLINE static void recalculate_max_e_jerk() {
866 866
         #define GET_MAX_E_JERK(N) SQRT(SQRT(0.5) * junction_deviation_mm * (N) * RECIPROCAL(1.0 - SQRT(0.5)))
867 867
         #if ENABLED(DISTINCT_E_FACTORS)

+ 2
- 2
Marlin/src/module/printcounter.h View File

@@ -28,7 +28,7 @@
28 28
 // Print debug messages with M111 S2
29 29
 //#define DEBUG_PRINTCOUNTER
30 30
 
31
-#if ENABLED(I2C_EEPROM) || ENABLED(SPI_EEPROM)
31
+#if EITHER(I2C_EEPROM, SPI_EEPROM)
32 32
   // round up address to next page boundary (assuming 32 byte pages)
33 33
   #define STATS_EEPROM_ADDRESS 0x40
34 34
 #else
@@ -57,7 +57,7 @@ class PrintCounter: public Stopwatch {
57 57
   private:
58 58
     typedef Stopwatch super;
59 59
 
60
-    #if ENABLED(I2C_EEPROM) || ENABLED(SPI_EEPROM) || defined(CPU_32_BIT)
60
+    #if EITHER(I2C_EEPROM, SPI_EEPROM) || defined(CPU_32_BIT)
61 61
       typedef uint32_t eeprom_address_t;
62 62
     #else
63 63
       typedef uint16_t eeprom_address_t;

+ 3
- 3
Marlin/src/module/probe.cpp View File

@@ -38,7 +38,7 @@
38 38
 #include "../gcode/gcode.h"
39 39
 #include "../lcd/ultralcd.h"
40 40
 
41
-#if ENABLED(BLTOUCH) || ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(PROBE_TRIGGERED_WHEN_STOWED_TEST) || (QUIET_PROBING && ENABLED(PROBING_STEPPERS_OFF))
41
+#if ANY(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY, PROBE_TRIGGERED_WHEN_STOWED_TEST) || (QUIET_PROBING && ENABLED(PROBING_STEPPERS_OFF))
42 42
   #include "../Marlin.h" // for stop(), disable_e_steppers
43 43
 #endif
44 44
 
@@ -416,7 +416,7 @@ bool set_probe_deployed(const bool deploy) {
416 416
   if (deploy_stow_condition && unknown_condition)
417 417
     do_probe_raise(MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_CLEARANCE_DEPLOY_PROBE));
418 418
 
419
-  #if ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY)
419
+  #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY)
420 420
     #if ENABLED(Z_PROBE_SLED)
421 421
       #define _AUE_ARGS true, false, false
422 422
     #else
@@ -553,7 +553,7 @@ static bool do_probe_move(const float z, const float fr_mm_s) {
553 553
 
554 554
   // Check to see if the probe was triggered
555 555
   const bool probe_triggered =
556
-    #if ENABLED(DELTA) && ENABLED(SENSORLESS_PROBING)
556
+    #if BOTH(DELTA, SENSORLESS_PROBING)
557 557
       endstops.trigger_state() & (_BV(X_MIN) | _BV(Y_MIN) | _BV(Z_MIN))
558 558
     #else
559 559
       TEST(endstops.trigger_state(),

+ 9
- 9
Marlin/src/module/stepper.cpp View File

@@ -153,7 +153,7 @@ bool Stepper::abort_current_block;
153 153
 #if Z_MULTI_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN)
154 154
   bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false;
155 155
 #endif
156
-#if ENABLED(Z_TRIPLE_ENDSTOPS) || (ENABLED(Z_STEPPER_AUTO_ALIGN) && ENABLED(Z_TRIPLE_STEPPER_DRIVERS))
156
+#if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS)
157 157
   bool Stepper::locked_Z3_motor = false;
158 158
 #endif
159 159
 
@@ -1450,7 +1450,7 @@ void Stepper::stepper_pulse_phase_isr() {
1450 1450
 
1451 1451
     // Pulse Extruders
1452 1452
     // Tick the E axis, correct error term and update position
1453
-    #if ENABLED(LIN_ADVANCE) || ENABLED(MIXING_EXTRUDER)
1453
+    #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER)
1454 1454
       delta_error[E_AXIS] += advance_dividend[E_AXIS];
1455 1455
       if (delta_error[E_AXIS] >= 0) {
1456 1456
         count_position[E_AXIS] += count_direction[E_AXIS];
@@ -1679,7 +1679,7 @@ uint32_t Stepper::stepper_block_phase_isr() {
1679 1679
          * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z, handled below)
1680 1680
          * If DeltaA ==  DeltaB, the movement is only in the 1st axis (X)
1681 1681
          */
1682
-        #if ENABLED(COREXY) || ENABLED(COREXZ)
1682
+        #if EITHER(COREXY, COREXZ)
1683 1683
           #define X_CMP ==
1684 1684
         #else
1685 1685
           #define X_CMP !=
@@ -1697,7 +1697,7 @@ uint32_t Stepper::stepper_block_phase_isr() {
1697 1697
          * If DeltaA ==  DeltaB, the movement is only in the 1st axis (X or Y)
1698 1698
          * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z)
1699 1699
          */
1700
-        #if ENABLED(COREYX) || ENABLED(COREYZ)
1700
+        #if EITHER(COREYX, COREYZ)
1701 1701
           #define Y_CMP ==
1702 1702
         #else
1703 1703
           #define Y_CMP !=
@@ -1715,7 +1715,7 @@ uint32_t Stepper::stepper_block_phase_isr() {
1715 1715
          * If DeltaA ==  DeltaB, the movement is only in the 1st axis (X or Y, already handled above)
1716 1716
          * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Z)
1717 1717
          */
1718
-        #if ENABLED(COREZX) || ENABLED(COREZY)
1718
+        #if EITHER(COREZX, COREZY)
1719 1719
           #define Z_CMP ==
1720 1720
         #else
1721 1721
           #define Z_CMP !=
@@ -2030,7 +2030,7 @@ void Stepper::init() {
2030 2030
   #if HAS_X_ENABLE
2031 2031
     X_ENABLE_INIT;
2032 2032
     if (!X_ENABLE_ON) X_ENABLE_WRITE(HIGH);
2033
-    #if (ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)) && HAS_X2_ENABLE
2033
+    #if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) && HAS_X2_ENABLE
2034 2034
       X2_ENABLE_INIT;
2035 2035
       if (!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH);
2036 2036
     #endif
@@ -2093,7 +2093,7 @@ void Stepper::init() {
2093 2093
 
2094 2094
   // Init Step Pins
2095 2095
   #if HAS_X_STEP
2096
-    #if ENABLED(X_DUAL_STEPPER_DRIVERS) || ENABLED(DUAL_X_CARRIAGE)
2096
+    #if EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE)
2097 2097
       X2_STEP_INIT;
2098 2098
       X2_STEP_WRITE(INVERT_X_STEP_PIN);
2099 2099
     #endif
@@ -2467,13 +2467,13 @@ void Stepper::report_positions() {
2467 2467
     if (!initialized) return;
2468 2468
     LOOP_L_N(i, COUNT(motor_current_setting)) {
2469 2469
       switch (i) {
2470
-        #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) || PIN_EXISTS(MOTOR_CURRENT_PWM_X) || PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
2470
+        #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y)
2471 2471
           case 0:
2472 2472
         #endif
2473 2473
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
2474 2474
           case 1:
2475 2475
         #endif
2476
-        #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) || PIN_EXISTS(MOTOR_CURRENT_PWM_E0) || PIN_EXISTS(MOTOR_CURRENT_PWM_E1)
2476
+        #if ANY_PIN(MOTOR_CURRENT_PWM_E, MOTOR_CURRENT_PWM_E0, MOTOR_CURRENT_PWM_E1)
2477 2477
           case 2:
2478 2478
         #endif
2479 2479
             digipot_current(i, motor_current_setting[i]);

+ 2
- 2
Marlin/src/module/stepper.h View File

@@ -267,7 +267,7 @@ class Stepper {
267 267
     #if Z_MULTI_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN)
268 268
       static bool locked_Z_motor, locked_Z2_motor;
269 269
     #endif
270
-    #if ENABLED(Z_TRIPLE_ENDSTOPS) || (ENABLED(Z_STEPPER_AUTO_ALIGN) && ENABLED(Z_TRIPLE_STEPPER_DRIVERS))
270
+    #if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS)
271 271
       static bool locked_Z3_motor;
272 272
     #endif
273 273
 
@@ -423,7 +423,7 @@ class Stepper {
423 423
       FORCE_INLINE static void set_z_lock(const bool state) { locked_Z_motor = state; }
424 424
       FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; }
425 425
     #endif
426
-    #if ENABLED(Z_TRIPLE_ENDSTOPS) || (ENABLED(Z_STEPPER_AUTO_ALIGN) && ENABLED(Z_TRIPLE_STEPPER_DRIVERS))
426
+    #if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS)
427 427
       FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; }
428 428
     #endif
429 429
 

+ 1
- 1
Marlin/src/module/stepper_indirection.h View File

@@ -618,7 +618,7 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
618 618
     #define    _REV_E_DIR(E)   do{ if (E == 0) { E0_DIR_WRITE( INVERT_E0_DIR); } else { E1_DIR_WRITE( INVERT_E1_DIR); } }while(0)
619 619
   #endif
620 620
 
621
-  #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(MULTI_NOZZLE_DUPLICATION)
621
+  #if EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION)
622 622
 
623 623
     #define NDIR(N) _DUPE(DIR,!INVERT_E##N##_DIR)
624 624
     #define RDIR(N) _DUPE(DIR, INVERT_E##N##_DIR)

+ 11
- 11
Marlin/src/module/temperature.cpp View File

@@ -33,13 +33,13 @@
33 33
 #include "../core/language.h"
34 34
 #include "../HAL/shared/Delay.h"
35 35
 
36
-#define MAX6675_SEPARATE_SPI (ENABLED(HEATER_0_USES_MAX6675) || ENABLED(HEATER_1_USES_MAX6675)) && PIN_EXISTS(MAX6675_SCK) && PIN_EXISTS(MAX6675_DO)
36
+#define MAX6675_SEPARATE_SPI EITHER(HEATER_0_USES_MAX6675, HEATER_1_USES_MAX6675) && PIN_EXISTS(MAX6675_SCK, MAX6675_DO)
37 37
 
38 38
 #if MAX6675_SEPARATE_SPI
39 39
   #include "../libs/private_spi.h"
40 40
 #endif
41 41
 
42
-#if ENABLED(BABYSTEPPING) || ENABLED(PID_EXTRUSION_SCALING)
42
+#if EITHER(BABYSTEPPING, PID_EXTRUSION_SCALING)
43 43
   #include "stepper.h"
44 44
 #endif
45 45
 
@@ -360,8 +360,8 @@ temp_range_t Temperature::temp_range[HOTENDS] = ARRAY_BY_HOTENDS(sensor_heater_0
360 360
     #endif
361 361
 
362 362
     #if WATCH_BED || WATCH_HOTENDS
363
-      #define HAS_TP_BED (ENABLED(THERMAL_PROTECTION_BED) && ENABLED(PIDTEMPBED))
364
-      #if HAS_TP_BED && ENABLED(THERMAL_PROTECTION_HOTENDS) && ENABLED(PIDTEMP)
363
+      #define HAS_TP_BED BOTH(THERMAL_PROTECTION_BED, PIDTEMPBED)
364
+      #if HAS_TP_BED && BOTH(THERMAL_PROTECTION_HOTENDS, PIDTEMP)
365 365
         #define GTV(B,H) (heater < 0 ? (B) : (H))
366 366
       #elif HAS_TP_BED
367 367
         #define GTV(B,H) (B)
@@ -913,7 +913,7 @@ void Temperature::manage_heater() {
913 913
     }
914 914
   #endif
915 915
 
916
-  #if ENABLED(PROBING_HEATERS_OFF) && ENABLED(BED_LIMIT_SWITCHING)
916
+  #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING)
917 917
     static bool last_pause_state;
918 918
   #endif
919 919
 
@@ -1004,12 +1004,12 @@ void Temperature::manage_heater() {
1004 1004
 
1005 1005
     #if DISABLED(PIDTEMPBED)
1006 1006
       if (PENDING(ms, next_bed_check_ms)
1007
-        #if ENABLED(PROBING_HEATERS_OFF) && ENABLED(BED_LIMIT_SWITCHING)
1007
+        #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING)
1008 1008
           && paused == last_pause_state
1009 1009
         #endif
1010 1010
       ) return;
1011 1011
       next_bed_check_ms = ms + BED_CHECK_INTERVAL;
1012
-      #if ENABLED(PROBING_HEATERS_OFF) && ENABLED(BED_LIMIT_SWITCHING)
1012
+      #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING)
1013 1013
         last_pause_state = paused;
1014 1014
       #endif
1015 1015
     #endif
@@ -1334,7 +1334,7 @@ void Temperature::init() {
1334 1334
   #endif
1335 1335
 
1336 1336
   #if MB(RUMBA)
1337
-    #define _AD(N) (ENABLED(HEATER_##N##_USES_AD595) || ENABLED(HEATER_##N##_USES_AD8495))
1337
+    #define _AD(N) (ANY(HEATER_##N##_USES_AD595, HEATER_##N##_USES_AD8495))
1338 1338
     #if _AD(0) || _AD(1) || _AD(2) || _AD(3) || _AD(4) || _AD(5) || _AD(BED) || _AD(CHAMBER)
1339 1339
       // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
1340 1340
       MCUCR = _BV(JTD);
@@ -1342,7 +1342,7 @@ void Temperature::init() {
1342 1342
     #endif
1343 1343
   #endif
1344 1344
 
1345
-  #if ENABLED(PIDTEMP) && ENABLED(PID_EXTRUSION_SCALING)
1345
+  #if BOTH(PIDTEMP, PID_EXTRUSION_SCALING)
1346 1346
     last_e_position = 0;
1347 1347
   #endif
1348 1348
 
@@ -2743,7 +2743,7 @@ void Temperature::isr() {
2743 2743
   //
2744 2744
 
2745 2745
   #if ENABLED(BABYSTEPPING)
2746
-    #if ENABLED(BABYSTEP_XY) || ENABLED(I2C_POSITION_ENCODERS)
2746
+    #if EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS)
2747 2747
       LOOP_XYZ(axis) {
2748 2748
         const int16_t curTodo = babystepsTodo[axis]; // get rid of volatile for performance
2749 2749
         if (curTodo) {
@@ -2942,7 +2942,7 @@ void Temperature::isr() {
2942 2942
 
2943 2943
   #endif // AUTO_REPORT_TEMPERATURES
2944 2944
 
2945
-  #if ENABLED(ULTRA_LCD) || ENABLED(EXTENSIBLE_UI)
2945
+  #if EITHER(ULTRA_LCD, EXTENSIBLE_UI)
2946 2946
     void Temperature::set_heating_message(const uint8_t e) {
2947 2947
       const bool heating = isHeatingHotend(e);
2948 2948
       #if HOTENDS > 1

+ 3
- 3
Marlin/src/module/temperature.h View File

@@ -739,7 +739,7 @@ class Temperature {
739 739
       #endif
740 740
     #endif
741 741
 
742
-    #if ENABLED(ULTRA_LCD) || ENABLED(EXTENSIBLE_UI)
742
+    #if EITHER(ULTRA_LCD, EXTENSIBLE_UI)
743 743
       static void set_heating_message(const uint8_t e);
744 744
     #endif
745 745
 
@@ -778,9 +778,9 @@ class Temperature {
778 778
 
779 779
     static void updateTemperaturesFromRawValues();
780 780
 
781
-    #define HAS_MAX6675 (ENABLED(HEATER_0_USES_MAX6675) || ENABLED(HEATER_1_USES_MAX6675))
781
+    #define HAS_MAX6675 EITHER(HEATER_0_USES_MAX6675, HEATER_1_USES_MAX6675)
782 782
     #if HAS_MAX6675
783
-      #if ENABLED(HEATER_0_USES_MAX6675) && ENABLED(HEATER_1_USES_MAX6675)
783
+      #if BOTH(HEATER_0_USES_MAX6675, HEATER_1_USES_MAX6675)
784 784
         #define COUNT_6675 2
785 785
       #else
786 786
         #define COUNT_6675 1

+ 2
- 2
Marlin/src/module/tool_change.cpp View File

@@ -49,7 +49,7 @@
49 49
   #include "../gcode/gcode.h" // for dwell()
50 50
 #endif
51 51
 
52
-#if ENABLED(SWITCHING_EXTRUDER) || ENABLED(SWITCHING_NOZZLE) || ENABLED(SWITCHING_TOOLHEAD)
52
+#if ANY(SWITCHING_EXTRUDER, SWITCHING_NOZZLE, SWITCHING_TOOLHEAD)
53 53
   #include "servo.h"
54 54
 #endif
55 55
 
@@ -740,7 +740,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
740 740
           singlenozzle_temp[active_extruder] = thermalManager.temp_hotend[0].target;
741 741
           if (singlenozzle_temp[tmp_extruder] && singlenozzle_temp[tmp_extruder] != singlenozzle_temp[active_extruder]) {
742 742
             thermalManager.setTargetHotend(singlenozzle_temp[tmp_extruder], 0);
743
-            #if ENABLED(ULTRA_LCD) || ENABLED(EXTENSIBLE_UI)
743
+            #if EITHER(ULTRA_LCD, EXTENSIBLE_UI)
744 744
               thermalManager.set_heating_message(0);
745 745
             #endif
746 746
             (void)thermalManager.wait_for_hotend(0, false);  // Wait for heating or cooling

+ 1
- 1
Marlin/src/pins/pins.h View File

@@ -874,7 +874,7 @@
874 874
 #define _EPIN(p,q) __EPIN(p,q)
875 875
 
876 876
 // The X2 axis, if any, should be the next open extruder port
877
-#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
877
+#if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS)
878 878
   #ifndef X2_STEP_PIN
879 879
     #define X2_STEP_PIN   _EPIN(E_STEPPERS, STEP)
880 880
     #define X2_DIR_PIN    _EPIN(E_STEPPERS, DIR)

+ 2
- 2
Marlin/src/pins/pins_3DRAG.h View File

@@ -75,7 +75,7 @@
75 75
 //
76 76
 // LCD / Controller
77 77
 //
78
-#if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)
78
+#if BOTH(ULTRA_LCD, NEWPANEL)
79 79
   #undef BEEPER_PIN
80 80
 
81 81
   #undef LCD_PINS_RS
@@ -154,7 +154,7 @@
154 154
     #define SPINDLE_LASER_PWM_PIN    46   // MUST BE HARDWARE PWM
155 155
     #define SPINDLE_LASER_ENABLE_PIN 62   // Pin should have a pullup!
156 156
     #define SPINDLE_DIR_PIN          48
157
-  #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)) // use expansion header if no LCD in use
157
+  #elif !BOTH(ULTRA_LCD, NEWPANEL)     // use expansion header if no LCD in use
158 158
     #define SPINDLE_LASER_ENABLE_PIN 16   // Pin should have a pullup/pulldown!
159 159
     #define SPINDLE_DIR_PIN          17
160 160
   #endif

+ 1
- 1
Marlin/src/pins/pins_ANET_10.h View File

@@ -162,7 +162,7 @@
162 162
     #define LCD_PINS_D6      16
163 163
     #define LCD_PINS_D7      17
164 164
     #define ADC_KEYPAD_PIN    1
165
-  #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(ANET_FULL_GRAPHICS_LCD)
165
+  #elif EITHER(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, ANET_FULL_GRAPHICS_LCD)
166 166
     // Pin definitions for the Anet A6 Full Graphics display and the RepRapDiscount Full Graphics
167 167
     // display using an adapter board  // https://go.aisler.net/benlye/anet-lcd-adapter/pcb
168 168
     // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748

+ 2
- 2
Marlin/src/pins/pins_AZTEEG_X3.h View File

@@ -53,7 +53,7 @@
53 53
 #undef STAT_LED_RED_PIN
54 54
 #undef STAT_LED_BLUE_PIN
55 55
 
56
-#if ENABLED(VIKI2) || ENABLED(miniVIKI)
56
+#if ANY(VIKI2, miniVIKI)
57 57
 
58 58
   #undef DOGLCD_A0
59 59
   #undef DOGLCD_CS
@@ -75,7 +75,7 @@
75 75
 //
76 76
 // Misc
77 77
 //
78
-#if ENABLED(CASE_LIGHT_ENABLE)  && PIN_EXISTS(CASE_LIGHT) && PIN_EXISTS(STAT_LED_RED) && STAT_LED_RED_PIN == CASE_LIGHT_PIN
78
+#if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT, STAT_LED_RED) && STAT_LED_RED_PIN == CASE_LIGHT_PIN
79 79
   #undef STAT_LED_RED_PIN
80 80
 #endif
81 81
 

+ 3
- 3
Marlin/src/pins/pins_AZTEEG_X3_PRO.h View File

@@ -139,7 +139,7 @@
139 139
 #undef BEEPER_PIN
140 140
 #define BEEPER_PIN         33
141 141
 
142
-#if ENABLED(VIKI2) || ENABLED(miniVIKI)
142
+#if ANY(VIKI2, miniVIKI)
143 143
   #undef SD_DETECT_PIN
144 144
   #define SD_DETECT_PIN    49   // For easy adapter board
145 145
   #undef BEEPER_PIN
@@ -152,7 +152,7 @@
152 152
 //
153 153
 // Misc. Functions
154 154
 //
155
-#if ENABLED(CASE_LIGHT_ENABLE)  && PIN_EXISTS(CASE_LIGHT) && defined(DOGLCD_A0) && DOGLCD_A0 == CASE_LIGHT_PIN
155
+#if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && defined(DOGLCD_A0) && DOGLCD_A0 == CASE_LIGHT_PIN
156 156
   #undef DOGLCD_A0              // Steal pin 44 for the case light; if you have a Viki2 and have connected it
157 157
   #define DOGLCD_A0        57   // following the Panucatt wiring diagram, you may need to tweak these pin assignments
158 158
                                 // as the wiring diagram uses pin 44 for DOGLCD_A0
@@ -166,7 +166,7 @@
166 166
 #undef SPINDLE_DIR_PIN
167 167
 
168 168
 #if ENABLED(SPINDLE_LASER_ENABLE)   // EXP2 header
169
-  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
169
+  #if ANY(VIKI2, miniVIKI)
170 170
     #undef BTN_EN2
171 171
     #define BTN_EN2             31   // need 7 for the spindle speed PWM
172 172
   #endif

+ 1
- 1
Marlin/src/pins/pins_AZTEEG_X5_GT.h View File

@@ -112,7 +112,7 @@
112 112
 // Display
113 113
 //
114 114
 
115
-#if ENABLED(VIKI2) || ENABLED(miniVIKI)
115
+#if ANY(VIKI2, miniVIKI)
116 116
   #define BEEPER_PIN       P1_31
117 117
   #define DOGLCD_A0        P2_06
118 118
   #define DOGLCD_CS        P0_16

+ 1
- 1
Marlin/src/pins/pins_AZTEEG_X5_MINI_WIFI.h View File

@@ -143,7 +143,7 @@
143 143
       //#define SHIFT_EN   P1_22   // (41)  J5-4 & AUX-4
144 144
     #endif
145 145
 
146
-    #if ENABLED(VIKI2) || ENABLED(miniVIKI)
146
+    #if ANY(VIKI2, miniVIKI)
147 147
       //#define LCD_SCREEN_ROT_180
148 148
 
149 149
       #define BEEPER_PIN   P1_30   // (37) may change if cable changes

+ 2
- 2
Marlin/src/pins/pins_BEAST.h View File

@@ -126,7 +126,7 @@
126 126
     #define LCD_PINS_RS         49   // CS chip select /SS chip slave select
127 127
     #define LCD_PINS_ENABLE     51   // SID (MOSI)
128 128
     #define LCD_PINS_D4         52   // SCK (CLK) clock
129
-  #elif ENABLED(NEWPANEL) && ENABLED(PANEL_ONE)
129
+  #elif BOTH(NEWPANEL, PANEL_ONE)
130 130
     #define LCD_PINS_RS         PB8
131 131
     #define LCD_PINS_ENABLE     PD2
132 132
     #define LCD_PINS_D4         PB12
@@ -193,7 +193,7 @@
193 193
       #define LCD_SDSS          53
194 194
       #define SD_DETECT_PIN     49
195 195
 
196
-    #elif ENABLED(VIKI2) || ENABLED(miniVIKI)
196
+    #elif ANY(VIKI2, miniVIKI)
197 197
 
198 198
       #define BEEPER_PIN        33
199 199
 

+ 2
- 2
Marlin/src/pins/pins_CHITU3D.h View File

@@ -125,7 +125,7 @@
125 125
     #define LCD_PINS_RS         49   // CS chip select /SS chip slave select
126 126
     #define LCD_PINS_ENABLE     51   // SID (MOSI)
127 127
     #define LCD_PINS_D4         52   // SCK (CLK) clock
128
-  #elif ENABLED(NEWPANEL) && ENABLED(PANEL_ONE)
128
+  #elif BOTH(NEWPANEL, PANEL_ONE)
129 129
     #define LCD_PINS_RS         PB8
130 130
     #define LCD_PINS_ENABLE     PD2
131 131
     #define LCD_PINS_D4         PB12
@@ -192,7 +192,7 @@
192 192
       #define LCD_SDSS          53
193 193
       #define SD_DETECT_PIN     49
194 194
 
195
-    #elif ENABLED(VIKI2) || ENABLED(miniVIKI)
195
+    #elif ANY(VIKI2, miniVIKI)
196 196
 
197 197
       #define BEEPER_PIN        33
198 198
 

+ 1
- 1
Marlin/src/pins/pins_FELIX2.h View File

@@ -49,7 +49,7 @@
49 49
 //
50 50
 // LCD / Controller
51 51
 //
52
-#if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)
52
+#if BOTH(ULTRA_LCD, NEWPANEL)
53 53
 
54 54
   #define SD_DETECT_PIN     6
55 55
 

+ 1
- 3
Marlin/src/pins/pins_FORMBOT_RAPTOR2.h View File

@@ -35,9 +35,7 @@
35 35
   #define FIL_RUNOUT_PIN   22
36 36
 #endif
37 37
 
38
-#define GREEDY_PANEL (   ENABLED(PANEL_ONE) || ENABLED(VIKI2)     \
39
-                      || ENABLED(miniVIKI)  || ENABLED(MINIPANEL) \
40
-                      || ENABLED(REPRAPWORLD_KEYPAD) )
38
+#define GREEDY_PANEL ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)
41 39
 
42 40
 //
43 41
 // M3/M4/M5 - Spindle/Laser Control

+ 1
- 1
Marlin/src/pins/pins_MEGATRONICS.h View File

@@ -104,7 +104,7 @@
104 104
 //
105 105
 #define BEEPER_PIN         33
106 106
 
107
-#if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)
107
+#if BOTH(ULTRA_LCD, NEWPANEL)
108 108
 
109 109
   #define LCD_PINS_RS     16
110 110
   #define LCD_PINS_ENABLE 17

+ 2
- 2
Marlin/src/pins/pins_MIGHTYBOARD_REVE.h View File

@@ -175,9 +175,9 @@
175 175
 #endif
176 176
 
177 177
 #ifndef FAN_PIN
178
-  #if ENABLED(IS_EFB) || ENABLED(IS_EFF)       // Hotend, Fan, Bed or Hotend, Fan, Fan
178
+  #if EITHER(IS_EFB, IS_EFF)                      // Hotend, Fan, Bed or Hotend, Fan, Fan
179 179
     #define FAN_PIN        EX2_HEAT_PIN
180
-  #elif ENABLED(IS_EEF) || ENABLED(IS_SF)      // Hotend, Hotend, Fan or Spindle, Fan
180
+  #elif EITHER(IS_EEF, IS_SF)                     // Hotend, Hotend, Fan or Spindle, Fan
181 181
     #define FAN_PIN        HBP_PIN
182 182
   #else
183 183
     #define FAN_PIN        EXTRA_FET_PIN

+ 1
- 1
Marlin/src/pins/pins_MKS_GEN_13.h View File

@@ -56,7 +56,7 @@
56 56
 //
57 57
 // LCD / Controller
58 58
 //
59
-#if ENABLED(VIKI2) || ENABLED(miniVIKI)
59
+#if ANY(VIKI2, miniVIKI)
60 60
   /**
61 61
    * VIKI2 Has two groups of wires with...
62 62
    *

+ 1
- 1
Marlin/src/pins/pins_MKS_SBASE.h View File

@@ -245,7 +245,7 @@
245 245
   #define LCD_SDSS         P0_28   // EXP2.4
246 246
   #define LCD_PINS_ENABLE  P0_18   // EXP1.3
247 247
   #define LCD_PINS_D4      P0_15   // EXP1.5
248
-  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
248
+  #if ANY(VIKI2, miniVIKI)
249 249
     #define DOGLCD_SCK     SCK_PIN
250 250
     #define DOGLCD_MOSI    MOSI_PIN
251 251
   #endif

+ 2
- 2
Marlin/src/pins/pins_PRINTRBOARD.h View File

@@ -123,7 +123,7 @@
123 123
 //
124 124
 // LCD / Controller
125 125
 //
126
-#if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)
126
+#if BOTH(ULTRA_LCD, NEWPANEL)
127 127
 
128 128
   #define LCD_PINS_RS       9   // E1       JP11-11
129 129
   #define LCD_PINS_ENABLE   8   // E0       JP11-10
@@ -132,7 +132,7 @@
132 132
   #define LCD_PINS_D6       5   // D5       JP11-6
133 133
   #define LCD_PINS_D7       4   // D4       JP11-5
134 134
 
135
-  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
135
+  #if ANY(VIKI2, miniVIKI)
136 136
     #define BEEPER_PIN      8   // E0       JP11-10
137 137
 
138 138
     #define DOGLCD_A0      40   // F2       JP2-2

+ 1
- 1
Marlin/src/pins/pins_PRINTRBOARD_REVF.h View File

@@ -208,7 +208,7 @@
208 208
   #define LCD_PINS_D6       5   // D5       JP11-6
209 209
   #define LCD_PINS_D7       4   // D4       JP11-5
210 210
 
211
-  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
211
+  #if ANY(VIKI2, miniVIKI)
212 212
 
213 213
     #define BEEPER_PIN      8   // E0       JP11-10
214 214
     #define DOGLCD_A0      40   // F2       JP2-2

+ 1
- 1
Marlin/src/pins/pins_RAMBO.h View File

@@ -175,7 +175,7 @@
175 175
     #define LCD_PINS_D6     74
176 176
     #define LCD_PINS_D7     75
177 177
 
178
-    #if ENABLED(VIKI2) || ENABLED(miniVIKI)
178
+    #if ANY(VIKI2, miniVIKI)
179 179
       #define BEEPER_PIN   44
180 180
       // NB: Panucatt's Viki 2.0 wiring diagram (v1.2) indicates that the
181 181
       //     beeper/buzzer is connected to pin 33; however, the pin used in the

+ 10
- 12
Marlin/src/pins/pins_RAMPS.h View File

@@ -199,13 +199,13 @@
199 199
 #endif
200 200
 
201 201
 #ifndef FAN_PIN
202
-  #if ENABLED(IS_RAMPS_EFB) || ENABLED(IS_RAMPS_EFF)  // Hotend, Fan, Bed or Hotend, Fan, Fan
202
+  #if EITHER(IS_RAMPS_EFB, IS_RAMPS_EFF)          // Hotend, Fan, Bed or Hotend, Fan, Fan
203 203
     #define FAN_PIN        RAMPS_D9_PIN
204
-  #elif ENABLED(IS_RAMPS_EEF) || ENABLED(IS_RAMPS_SF) // Hotend, Hotend, Fan or Spindle, Fan
204
+  #elif EITHER(IS_RAMPS_EEF, IS_RAMPS_SF)         // Hotend, Hotend, Fan or Spindle, Fan
205 205
     #define FAN_PIN        RAMPS_D8_PIN
206
-  #elif ENABLED(IS_RAMPS_EEB)                         // Hotend, Hotend, Bed
207
-    #define FAN_PIN         4   // IO pin. Buffer needed
208
-  #else                                               // Non-specific are "EFB" (i.e., "EFBF" or "EFBE")
206
+  #elif ENABLED(IS_RAMPS_EEB)                  // Hotend, Hotend, Bed
207
+    #define FAN_PIN         4                  // IO pin. Buffer needed
208
+  #else                                        // Non-specific are "EFB" (i.e., "EFBF" or "EFBE")
209 209
     #define FAN_PIN        RAMPS_D9_PIN
210 210
   #endif
211 211
 #endif
@@ -232,8 +232,7 @@
232 232
 #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENABLE_PIN)
233 233
   #if NUM_SERVOS <= 1 // try to use servo connector first
234 234
     #define CASE_LIGHT_PIN    6   // MUST BE HARDWARE PWM
235
-  #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \
236
-      && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD)))  // try to use AUX 2
235
+  #elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD))  // try to use AUX 2
237 236
     #define CASE_LIGHT_PIN   44   // MUST BE HARDWARE PWM
238 237
   #endif
239 238
 #endif
@@ -246,8 +245,7 @@
246 245
     #define SPINDLE_LASER_ENABLE_PIN  4   // Pin should have a pullup/pulldown!
247 246
     #define SPINDLE_LASER_PWM_PIN     6   // MUST BE HARDWARE PWM
248 247
     #define SPINDLE_DIR_PIN           5
249
-  #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \
250
-      && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD)))  // try to use AUX 2
248
+  #elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD))  // try to use AUX 2
251 249
     #define SPINDLE_LASER_ENABLE_PIN 40   // Pin should have a pullup/pulldown!
252 250
     #define SPINDLE_LASER_PWM_PIN    44   // MUST BE HARDWARE PWM
253 251
     #define SPINDLE_DIR_PIN          65
@@ -347,7 +345,7 @@
347 345
     #define LCD_PINS_ENABLE     51   // SID (MOSI)
348 346
     #define LCD_PINS_D4         52   // SCK (CLK) clock
349 347
 
350
-  #elif ENABLED(NEWPANEL) && ENABLED(PANEL_ONE)
348
+  #elif BOTH(NEWPANEL, PANEL_ONE)
351 349
 
352 350
     #define LCD_PINS_RS         40
353 351
     #define LCD_PINS_ENABLE     42
@@ -379,7 +377,7 @@
379 377
 
380 378
     #else
381 379
 
382
-      #if ENABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306)
380
+      #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306)
383 381
         #define LCD_PINS_DC     25   // Set as output on init
384 382
         #define LCD_PINS_RS     27   // Pull low for 1s to init
385 383
         // DOGM SPI LCD Support
@@ -463,7 +461,7 @@
463 461
       #define LCD_SDSS          SDSS
464 462
       #define SD_DETECT_PIN     49
465 463
 
466
-    #elif ENABLED(VIKI2) || ENABLED(miniVIKI)
464
+    #elif ANY(VIKI2, miniVIKI)
467 465
 
468 466
       #define DOGLCD_CS         45
469 467
       #define DOGLCD_A0         44

+ 1
- 1
Marlin/src/pins/pins_RAMPS_DUO.h View File

@@ -76,7 +76,7 @@
76 76
 //
77 77
 #if ENABLED(ULTRA_LCD)
78 78
 
79
-  #if ENABLED(NEWPANEL) && ENABLED(PANEL_ONE)
79
+  #if BOTH(NEWPANEL, PANEL_ONE)
80 80
     #undef LCD_PINS_D4
81 81
     #define LCD_PINS_D4  68
82 82
 

+ 1
- 1
Marlin/src/pins/pins_RAMPS_FD_V1.h View File

@@ -161,7 +161,7 @@
161 161
     #define DOGLCD_A0      27
162 162
   #endif
163 163
 
164
-  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
164
+  #if ANY(VIKI2, miniVIKI)
165 165
     #define DOGLCD_A0           16
166 166
     #define KILL_PIN            51
167 167
     #define STAT_LED_BLUE_PIN   29

+ 5
- 7
Marlin/src/pins/pins_RAMPS_LINUX.h View File

@@ -220,8 +220,7 @@
220 220
 #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENABLE_PIN)
221 221
   #if NUM_SERVOS <= 1 // try to use servo connector first
222 222
     #define CASE_LIGHT_PIN    6   // MUST BE HARDWARE PWM
223
-  #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \
224
-      && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD)))  // try to use AUX 2
223
+  #elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD))  // try to use AUX 2
225 224
     #define CASE_LIGHT_PIN   44   // MUST BE HARDWARE PWM
226 225
   #endif
227 226
 #endif
@@ -234,8 +233,7 @@
234 233
     #define SPINDLE_LASER_ENABLE_PIN  4   // Pin should have a pullup/pulldown!
235 234
     #define SPINDLE_LASER_PWM_PIN     6   // MUST BE HARDWARE PWM
236 235
     #define SPINDLE_DIR_PIN           5
237
-  #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \
238
-      && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD)))  // try to use AUX 2
236
+  #elif !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD))  // try to use AUX 2
239 237
     #define SPINDLE_LASER_ENABLE_PIN 40   // Pin should have a pullup/pulldown!
240 238
     #define SPINDLE_LASER_PWM_PIN    44   // MUST BE HARDWARE PWM
241 239
     #define SPINDLE_DIR_PIN          65
@@ -335,7 +333,7 @@
335 333
     #define LCD_PINS_ENABLE     51   // SID (MOSI)
336 334
     #define LCD_PINS_D4         52   // SCK (CLK) clock
337 335
 
338
-  #elif ENABLED(NEWPANEL) && ENABLED(PANEL_ONE)
336
+  #elif BOTH(NEWPANEL, PANEL_ONE)
339 337
 
340 338
     #define LCD_PINS_RS         40
341 339
     #define LCD_PINS_ENABLE     42
@@ -367,7 +365,7 @@
367 365
 
368 366
     #else
369 367
 
370
-      #if ENABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306)
368
+      #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306)
371 369
         #define LCD_PINS_DC     25   // Set as output on init
372 370
         #define LCD_PINS_RS     27   // Pull low for 1s to init
373 371
         // DOGM SPI LCD Support
@@ -451,7 +449,7 @@
451 449
       #define LCD_SDSS          SDSS
452 450
       #define SD_DETECT_PIN     49
453 451
 
454
-    #elif ENABLED(VIKI2) || ENABLED(miniVIKI)
452
+    #elif ANY(VIKI2, miniVIKI)
455 453
 
456 454
       #define DOGLCD_CS         45
457 455
       #define DOGLCD_A0         44

+ 1
- 1
Marlin/src/pins/pins_RAMPS_PLUS.h View File

@@ -73,7 +73,7 @@
73 73
 #undef E0_CS_PIN
74 74
 #undef E1_CS_PIN
75 75
 
76
-#if ENABLED(ULTRA_LCD) && DISABLED(REPRAPWORLD_GRAPHICAL_LCD) && (DISABLED(NEWPANEL) || DISABLED(PANEL_ONE)) && DISABLED(CR10_STOCKDISPLAY)
76
+#if ENABLED(ULTRA_LCD) && DISABLED(REPRAPWORLD_GRAPHICAL_LCD) && !BOTH(NEWPANEL, PANEL_ONE) && DISABLED(CR10_STOCKDISPLAY)
77 77
   #if DISABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306)
78 78
     #undef LCD_PINS_RS
79 79
     #define LCD_PINS_RS     42   // 3DYMY boards pin 16 -> 42

+ 6
- 6
Marlin/src/pins/pins_RAMPS_RE_ARM.h View File

@@ -173,13 +173,13 @@
173 173
 #endif
174 174
 
175 175
 #ifndef FAN_PIN
176
-  #if ENABLED(IS_RAMPS_EFB) || ENABLED(IS_RAMPS_EFF)   // Hotend, Fan, Bed or Hotend, Fan, Fan
176
+  #if EITHER(IS_RAMPS_EFB, IS_RAMPS_EFF)          // Hotend, Fan, Bed or Hotend, Fan, Fan
177 177
     #define FAN_PIN        RAMPS_D9_PIN
178
-  #elif ENABLED(IS_RAMPS_EEF) || ENABLED(IS_RAMPS_SF)  // Hotend, Hotend, Fan or Spindle, Fan
178
+  #elif EITHER(IS_RAMPS_EEF, IS_RAMPS_SF)         // Hotend, Hotend, Fan or Spindle, Fan
179 179
     #define FAN_PIN        RAMPS_D8_PIN
180
-  #elif ENABLED(IS_RAMPS_EEB)                          // Hotend, Hotend, Bed
181
-    #define FAN_PIN        P1_18   // (4) IO pin. Buffer needed
182
-  #else                                                // Non-specific are "EFB" (i.e., "EFBF" or "EFBE")
180
+  #elif ENABLED(IS_RAMPS_EEB)                  // Hotend, Hotend, Bed
181
+    #define FAN_PIN        P1_18               // (4) IO pin. Buffer needed
182
+  #else                                        // Non-specific are "EFB" (i.e., "EFBF" or "EFBE")
183 183
     #define FAN_PIN        RAMPS_D9_PIN
184 184
   #endif
185 185
 #endif
@@ -293,7 +293,7 @@
293 293
     //#define SHIFT_EN     P1_22   // (41)  J5-4 & AUX-4
294 294
   #endif
295 295
 
296
-  #if ENABLED(VIKI2) || ENABLED(miniVIKI)
296
+  #if ANY(VIKI2, miniVIKI)
297 297
     // #define LCD_SCREEN_ROT_180
298 298
 
299 299
     #define BTN_EN1        P3_26   // (31) J3-2 & AUX-4

+ 1
- 1
Marlin/src/pins/pins_RUMBA.h View File

@@ -167,7 +167,7 @@
167 167
 //
168 168
 // LCD / Controller
169 169
 //
170
-#if ENABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306)
170
+#if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306)
171 171
   #define LCD_PINS_DC      38   // Set as output on init
172 172
   #define LCD_PINS_RS      41   // Pull low for 1s to init
173 173
   // DOGM SPI LCD Support

+ 0
- 0
Marlin/src/pins/pins_RURAMPS4D_11.h View File


Some files were not shown because too many files changed in this diff

Loading…
Cancel
Save