Browse Source

Fix MIN/MAX function collision with macros

Scott Lahteine 6 years ago
parent
commit
750a16ad38
63 changed files with 167 additions and 167 deletions
  1. 1
    1
      Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c
  2. 1
    1
      Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.h
  3. 1
    1
      Marlin/src/HAL/HAL_LINUX/main.cpp
  4. 1
    1
      Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp
  5. 2
    2
      Marlin/src/HAL/HAL_STM32F1/HAL_timers_STM32F1.cpp
  6. 1
    1
      Marlin/src/core/macros.h
  7. 4
    4
      Marlin/src/core/minmax.h
  8. 1
    1
      Marlin/src/feature/Max7219_Debug_LEDs.cpp
  9. 1
    1
      Marlin/src/feature/backlash.cpp
  10. 1
    1
      Marlin/src/feature/backlash.h
  11. 3
    3
      Marlin/src/feature/bedlevel/abl/abl.cpp
  12. 2
    2
      Marlin/src/feature/bedlevel/bedlevel.cpp
  13. 1
    1
      Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp
  14. 5
    5
      Marlin/src/feature/bedlevel/ubl/ubl.h
  15. 6
    6
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  16. 1
    1
      Marlin/src/feature/bltouch.cpp
  17. 1
    1
      Marlin/src/feature/dac/dac_mcp4728.cpp
  18. 1
    1
      Marlin/src/feature/digipot/digipot_mcp4018.cpp
  19. 1
    1
      Marlin/src/feature/digipot/digipot_mcp4451.cpp
  20. 2
    2
      Marlin/src/feature/leds/tempstat.cpp
  21. 1
    1
      Marlin/src/feature/mixing.cpp
  22. 2
    2
      Marlin/src/feature/mixing.h
  23. 5
    5
      Marlin/src/gcode/bedlevel/abl/G29.cpp
  24. 1
    1
      Marlin/src/gcode/bedlevel/mbl/G29.cpp
  25. 1
    1
      Marlin/src/gcode/calibrate/G28.cpp
  26. 1
    1
      Marlin/src/gcode/calibrate/G33.cpp
  27. 6
    6
      Marlin/src/gcode/calibrate/G34_M422.cpp
  28. 3
    3
      Marlin/src/gcode/calibrate/G425.cpp
  29. 1
    1
      Marlin/src/gcode/calibrate/M48.cpp
  30. 1
    1
      Marlin/src/gcode/control/M605.cpp
  31. 4
    4
      Marlin/src/gcode/feature/pause/M701_M702.cpp
  32. 1
    1
      Marlin/src/gcode/feature/trinamic/M122.cpp
  33. 1
    1
      Marlin/src/gcode/temperature/M106_M107.cpp
  34. 13
    13
      Marlin/src/inc/Conditionals_post.h
  35. 1
    1
      Marlin/src/inc/SanityCheck.h
  36. 2
    2
      Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
  37. 1
    1
      Marlin/src/lcd/dogm/dogm_Statusscreen.h
  38. 1
    1
      Marlin/src/lcd/dogm/status_screen_DOGM.cpp
  39. 1
    1
      Marlin/src/lcd/dogm/ultralcd_DOGM.cpp
  40. 1
    1
      Marlin/src/lcd/extensible_ui/ui_api.cpp
  41. 2
    2
      Marlin/src/lcd/extui_malyan_lcd.cpp
  42. 2
    2
      Marlin/src/lcd/menu/game/maze.cpp
  43. 12
    12
      Marlin/src/lcd/menu/game/snake.cpp
  44. 1
    1
      Marlin/src/lcd/menu/menu.cpp
  45. 2
    2
      Marlin/src/lcd/menu/menu.h
  46. 10
    10
      Marlin/src/lcd/menu/menu_configuration.cpp
  47. 1
    1
      Marlin/src/lcd/menu/menu_delta_calibrate.cpp
  48. 1
    1
      Marlin/src/lcd/menu/menu_temperature.cpp
  49. 1
    1
      Marlin/src/lcd/ultralcd.cpp
  50. 1
    1
      Marlin/src/lcd/ultralcd.h
  51. 4
    4
      Marlin/src/libs/least_squares_fit.h
  52. 2
    2
      Marlin/src/libs/nozzle.cpp
  53. 1
    1
      Marlin/src/module/configuration_store.cpp
  54. 5
    5
      Marlin/src/module/motion.cpp
  55. 12
    12
      Marlin/src/module/planner.cpp
  56. 1
    1
      Marlin/src/module/planner.h
  57. 3
    3
      Marlin/src/module/printcounter.cpp
  58. 2
    2
      Marlin/src/module/probe.cpp
  59. 2
    2
      Marlin/src/module/stepper.cpp
  60. 3
    3
      Marlin/src/module/stepper.h
  61. 8
    8
      Marlin/src/module/temperature.cpp
  62. 5
    5
      Marlin/src/module/temperature.h
  63. 1
    1
      Marlin/src/module/tool_change.cpp

+ 1
- 1
Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c View File

1904
 		ptr_src = &ptr_job->buf[ptr_job->buf_cnt];
1904
 		ptr_src = &ptr_job->buf[ptr_job->buf_cnt];
1905
 		nb_remain = ptr_job->buf_size - ptr_job->buf_cnt;
1905
 		nb_remain = ptr_job->buf_size - ptr_job->buf_cnt;
1906
 		// Fill a bank even if no data (ZLP)
1906
 		// Fill a bank even if no data (ZLP)
1907
-		nb_data = MIN(nb_remain, pkt_size);
1907
+		nb_data = _MIN(nb_remain, pkt_size);
1908
 		// Modify job information
1908
 		// Modify job information
1909
 		ptr_job->buf_cnt += nb_data;
1909
 		ptr_job->buf_cnt += nb_data;
1910
 		ptr_job->buf_load = nb_data;
1910
 		ptr_job->buf_load = nb_data;

+ 1
- 1
Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.h View File

291
   //! available greater size, then applies register format of UOTGHS controller
291
   //! available greater size, then applies register format of UOTGHS controller
292
   //! for endpoint size bit-field.
292
   //! for endpoint size bit-field.
293
 #undef udd_format_endpoint_size
293
 #undef udd_format_endpoint_size
294
-#define udd_format_endpoint_size(size)            (32 - clz(((uint32_t)MIN(MAX(size, 8), 1024) << 1) - 1) - 1 - 3)
294
+#define udd_format_endpoint_size(size)            (32 - clz(((uint32_t)_MIN(_MAX(size, 8), 1024) << 1) - 1) - 1 - 3)
295
   //! Configures the selected endpoint size
295
   //! Configures the selected endpoint size
296
 #define udd_configure_endpoint_size(ep, size)     (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPSIZE_Msk, udd_format_endpoint_size(size)))
296
 #define udd_configure_endpoint_size(ep, size)     (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPSIZE_Msk, udd_format_endpoint_size(size)))
297
   //! Gets the configured selected endpoint size
297
   //! Gets the configured selected endpoint size

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

49
 void read_serial_thread() {
49
 void read_serial_thread() {
50
   char buffer[255] = {};
50
   char buffer[255] = {};
51
   for (;;) {
51
   for (;;) {
52
-    std::size_t len = MIN(usb_serial.receive_buffer.free(), 254U);
52
+    std::size_t len = _MIN(usb_serial.receive_buffer.free(), 254U);
53
     if (fgets(buffer, len, stdin))
53
     if (fgets(buffer, len, stdin))
54
       for (std::size_t i = 0; i < strlen(buffer); i++)
54
       for (std::size_t i = 0; i < strlen(buffer); i++)
55
         usb_serial.receive_buffer.write(buffer[i]);
55
         usb_serial.receive_buffer.write(buffer[i]);

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

162
     // setup for SPI mode
162
     // setup for SPI mode
163
     SSP_CFG_Type HW_SPI_init; // data structure to hold init values
163
     SSP_CFG_Type HW_SPI_init; // data structure to hold init values
164
     SSP_ConfigStructInit(&HW_SPI_init);  // set values for SPI mode
164
     SSP_ConfigStructInit(&HW_SPI_init);  // set values for SPI mode
165
-    HW_SPI_init.ClockRate = Marlin_speed[MIN(spiRate, 6)]; // put in the specified bit rate
165
+    HW_SPI_init.ClockRate = Marlin_speed[_MIN(spiRate, 6)]; // put in the specified bit rate
166
     HW_SPI_init.Mode |= SSP_CR1_SSP_EN;
166
     HW_SPI_init.Mode |= SSP_CR1_SSP_EN;
167
     SSP_Init(LPC_SSPn, &HW_SPI_init);  // puts the values into the proper bits in the SSP0 registers
167
     SSP_Init(LPC_SSPn, &HW_SPI_init);  // puts the values into the proper bits in the SSP0 registers
168
   }
168
   }

+ 2
- 2
Marlin/src/HAL/HAL_STM32F1/HAL_timers_STM32F1.cpp View File

110
       timer_set_prescaler(STEP_TIMER_DEV, (uint16_t)(STEPPER_TIMER_PRESCALE - 1));
110
       timer_set_prescaler(STEP_TIMER_DEV, (uint16_t)(STEPPER_TIMER_PRESCALE - 1));
111
       timer_set_reload(STEP_TIMER_DEV, 0xFFFF);
111
       timer_set_reload(STEP_TIMER_DEV, 0xFFFF);
112
       timer_oc_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OC_MODE_FROZEN, TIMER_OC_NO_PRELOAD); // no output pin change
112
       timer_oc_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OC_MODE_FROZEN, TIMER_OC_NO_PRELOAD); // no output pin change
113
-      timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE / frequency)));
113
+      timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE / frequency)));
114
       timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
114
       timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
115
       timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
115
       timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
116
       nvic_irq_set_priority(irq_num, STEP_TIMER_IRQ_PRIO);
116
       nvic_irq_set_priority(irq_num, STEP_TIMER_IRQ_PRIO);
123
       timer_set_count(TEMP_TIMER_DEV, 0);
123
       timer_set_count(TEMP_TIMER_DEV, 0);
124
       timer_set_prescaler(TEMP_TIMER_DEV, (uint16_t)(TEMP_TIMER_PRESCALE - 1));
124
       timer_set_prescaler(TEMP_TIMER_DEV, (uint16_t)(TEMP_TIMER_PRESCALE - 1));
125
       timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
125
       timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
126
-      timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), ((F_CPU / TEMP_TIMER_PRESCALE) / frequency)));
126
+      timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), ((F_CPU / TEMP_TIMER_PRESCALE) / frequency)));
127
       timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
127
       timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
128
       nvic_irq_set_priority(irq_num, TEMP_TIMER_IRQ_PRIO);
128
       nvic_irq_set_priority(irq_num, TEMP_TIMER_IRQ_PRIO);
129
       timer_generate_update(TEMP_TIMER_DEV);
129
       timer_generate_update(TEMP_TIMER_DEV);

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

190
 #define ZERO(a)             memset(a,0,sizeof(a))
190
 #define ZERO(a)             memset(a,0,sizeof(a))
191
 #define COPY(a,b) do{ \
191
 #define COPY(a,b) do{ \
192
     static_assert(sizeof(a[0]) == sizeof(b[0]), "COPY: '" STRINGIFY(a) "' and '" STRINGIFY(b) "' types (sizes) don't match!"); \
192
     static_assert(sizeof(a[0]) == sizeof(b[0]), "COPY: '" STRINGIFY(a) "' and '" STRINGIFY(b) "' types (sizes) don't match!"); \
193
-    memcpy(&a[0],&b[0],MIN(sizeof(a),sizeof(b))); \
193
+    memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \
194
   }while(0)
194
   }while(0)
195
 
195
 
196
 // Macros for initializing arrays
196
 // Macros for initializing arrays

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

36
     extern "C++" {
36
     extern "C++" {
37
 
37
 
38
       // C++11 solution that is standards compliant. Return type is deduced automatically
38
       // C++11 solution that is standards compliant. Return type is deduced automatically
39
-      template <class L, class R> static inline constexpr auto MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) {
39
+      template <class L, class R> static inline constexpr auto _MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) {
40
         return lhs < rhs ? lhs : rhs;
40
         return lhs < rhs ? lhs : rhs;
41
       }
41
       }
42
-      template <class L, class R> static inline constexpr auto MAX(const L lhs, const R rhs) -> decltype(lhs + rhs) {
42
+      template <class L, class R> static inline constexpr auto _MAX(const L lhs, const R rhs) -> decltype(lhs + rhs) {
43
         return lhs > rhs ? lhs : rhs;
43
         return lhs > rhs ? lhs : rhs;
44
       }
44
       }
45
-      template<class T, class ... Ts> static inline constexpr const T MIN(T V, Ts... Vs) { return MIN(V, MIN(Vs...)); }
46
-      template<class T, class ... Ts> static inline constexpr const T MAX(T V, Ts... Vs) { return MAX(V, MAX(Vs...)); }
45
+      template<class T, class ... Ts> static inline constexpr const T _MIN(T V, Ts... Vs) { return _MIN(V, _MIN(Vs...)); }
46
+      template<class T, class ... Ts> static inline constexpr const T _MAX(T V, Ts... Vs) { return _MAX(V, _MAX(Vs...)); }
47
 
47
 
48
     }
48
     }
49
 
49
 

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

503
 
503
 
504
 // Apply changes to update a quantity
504
 // Apply changes to update a quantity
505
 void Max7219::quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv) {
505
 void Max7219::quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv) {
506
-  for (uint8_t i = MIN(nv, ov); i < MAX(nv, ov); i++)
506
+  for (uint8_t i = _MIN(nv, ov); i < _MAX(nv, ov); i++)
507
     #if MAX7219_X_LEDS == 8
507
     #if MAX7219_X_LEDS == 8
508
       #if MAX7219_Y_LEDS == 8
508
       #if MAX7219_Y_LEDS == 8
509
         led_set(i >> 1, y + (i & 1), nv >= ov); // single 8x8 LED matrix.  Use two lines to get 16 LED's
509
         led_set(i >> 1, y + (i & 1), nv >= ov); // single 8x8 LED matrix.  Use two lines to get 16 LED's

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

106
           // the current segment travels in the same direction as the correction
106
           // the current segment travels in the same direction as the correction
107
           if (reversing == (error_correction < 0)) {
107
           if (reversing == (error_correction < 0)) {
108
             if (segment_proportion == 0)
108
             if (segment_proportion == 0)
109
-              segment_proportion = MIN(1.0f, block->millimeters / smoothing_mm);
109
+              segment_proportion = _MIN(1.0f, block->millimeters / smoothing_mm);
110
             error_correction = CEIL(segment_proportion * error_correction);
110
             error_correction = CEIL(segment_proportion * error_correction);
111
           }
111
           }
112
           else
112
           else

+ 1
- 1
Marlin/src/feature/backlash.h View File

41
     #ifdef BACKLASH_SMOOTHING_MM
41
     #ifdef BACKLASH_SMOOTHING_MM
42
       static float smoothing_mm;
42
       static float smoothing_mm;
43
     #endif
43
     #endif
44
-    static inline void set_correction(const float &v) { correction = MAX(0, MIN(1.0, v)) * all_on; }
44
+    static inline void set_correction(const float &v) { correction = _MAX(0, _MIN(1.0, v)) * all_on; }
45
     static inline float get_correction() { return float(ui8_to_percent(correction)) / 100.0f; }
45
     static inline float get_correction() { return float(ui8_to_percent(correction)) / 100.0f; }
46
   #else
46
   #else
47
     static constexpr uint8_t correction = (BACKLASH_CORRECTION) * 0xFF;
47
     static constexpr uint8_t correction = (BACKLASH_CORRECTION) * 0xFF;

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

301
     #endif
301
     #endif
302
 
302
 
303
     gridx = gx;
303
     gridx = gx;
304
-    nextx = MIN(gridx + 1, ABL_BG_POINTS_X - 1);
304
+    nextx = _MIN(gridx + 1, ABL_BG_POINTS_X - 1);
305
   }
305
   }
306
 
306
 
307
   if (last_y != ry || last_gridx != gridx) {
307
   if (last_y != ry || last_gridx != gridx) {
318
       #endif
318
       #endif
319
 
319
 
320
       gridy = gy;
320
       gridy = gy;
321
-      nexty = MIN(gridy + 1, ABL_BG_POINTS_Y - 1);
321
+      nexty = _MIN(gridy + 1, ABL_BG_POINTS_Y - 1);
322
     }
322
     }
323
 
323
 
324
     if (last_gridx != gridx || last_gridy != gridy) {
324
     if (last_gridx != gridx || last_gridy != gridy) {
384
     #define LINE_SEGMENT_END(A) (current_position[_AXIS(A)] + (destination[_AXIS(A)] - current_position[_AXIS(A)]) * normalized_dist)
384
     #define LINE_SEGMENT_END(A) (current_position[_AXIS(A)] + (destination[_AXIS(A)] - current_position[_AXIS(A)]) * normalized_dist)
385
 
385
 
386
     float normalized_dist, end[XYZE];
386
     float normalized_dist, end[XYZE];
387
-    const int8_t gcx = MAX(cx1, cx2), gcy = MAX(cy1, cy2);
387
+    const int8_t gcx = _MAX(cx1, cx2), gcy = _MAX(cy1, cy2);
388
 
388
 
389
     // Crosses on the X and not already split on this X?
389
     // Crosses on the X and not already split on this X?
390
     // The x_splits flags are insurance against rounding errors.
390
     // The x_splits flags are insurance against rounding errors.

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

222
     #ifdef MANUAL_PROBE_START_Z
222
     #ifdef MANUAL_PROBE_START_Z
223
       #if MANUAL_PROBE_HEIGHT > 0
223
       #if MANUAL_PROBE_HEIGHT > 0
224
         do_blocking_move_to(rx, ry, MANUAL_PROBE_HEIGHT);
224
         do_blocking_move_to(rx, ry, MANUAL_PROBE_HEIGHT);
225
-        do_blocking_move_to_z(MAX(0,MANUAL_PROBE_START_Z));
225
+        do_blocking_move_to_z(_MAX(0,MANUAL_PROBE_START_Z));
226
       #else
226
       #else
227
-        do_blocking_move_to(rx, ry, MAX(0,MANUAL_PROBE_START_Z));
227
+        do_blocking_move_to(rx, ry, _MAX(0,MANUAL_PROBE_START_Z));
228
       #endif
228
       #endif
229
     #elif MANUAL_PROBE_HEIGHT > 0
229
     #elif MANUAL_PROBE_HEIGHT > 0
230
       const float prev_z = current_position[Z_AXIS];
230
       const float prev_z = current_position[Z_AXIS];

+ 1
- 1
Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp View File

81
       #define MBL_SEGMENT_END(A) (current_position[_AXIS(A)] + (destination[_AXIS(A)] - current_position[_AXIS(A)]) * normalized_dist)
81
       #define MBL_SEGMENT_END(A) (current_position[_AXIS(A)] + (destination[_AXIS(A)] - current_position[_AXIS(A)]) * normalized_dist)
82
 
82
 
83
       float normalized_dist, end[XYZE];
83
       float normalized_dist, end[XYZE];
84
-      const int8_t gcx = MAX(cx1, cx2), gcy = MAX(cy1, cy2);
84
+      const int8_t gcx = _MAX(cx1, cx2), gcy = _MAX(cy1, cy2);
85
 
85
 
86
       // Crosses on the X and not already split on this X?
86
       // Crosses on the X and not already split on this X?
87
       // The x_splits flags are insurance against rounding errors.
87
       // The x_splits flags are insurance against rounding errors.

+ 5
- 5
Marlin/src/feature/bedlevel/ubl/ubl.h View File

213
       const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * (1.0f / (MESH_X_DIST)),
213
       const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * (1.0f / (MESH_X_DIST)),
214
                   z1 = z_values[x1_i][yi];
214
                   z1 = z_values[x1_i][yi];
215
 
215
 
216
-      return z1 + xratio * (z_values[MIN(x1_i, GRID_MAX_POINTS_X - 2) + 1][yi] - z1); // Don't allow x1_i+1 to be past the end of the array
216
+      return z1 + xratio * (z_values[_MIN(x1_i, GRID_MAX_POINTS_X - 2) + 1][yi] - z1); // Don't allow x1_i+1 to be past the end of the array
217
                                                                                       // If it is, it is clamped to the last element of the
217
                                                                                       // If it is, it is clamped to the last element of the
218
                                                                                       // z_values[][] array and no correction is applied.
218
                                                                                       // z_values[][] array and no correction is applied.
219
     }
219
     }
242
       const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * (1.0f / (MESH_Y_DIST)),
242
       const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * (1.0f / (MESH_Y_DIST)),
243
                   z1 = z_values[xi][y1_i];
243
                   z1 = z_values[xi][y1_i];
244
 
244
 
245
-      return z1 + yratio * (z_values[xi][MIN(y1_i, GRID_MAX_POINTS_Y - 2) + 1] - z1); // Don't allow y1_i+1 to be past the end of the array
245
+      return z1 + yratio * (z_values[xi][_MIN(y1_i, GRID_MAX_POINTS_Y - 2) + 1] - z1); // Don't allow y1_i+1 to be past the end of the array
246
                                                                                       // If it is, it is clamped to the last element of the
246
                                                                                       // If it is, it is clamped to the last element of the
247
                                                                                       // z_values[][] array and no correction is applied.
247
                                                                                       // z_values[][] array and no correction is applied.
248
     }
248
     }
268
 
268
 
269
       const float z1 = calc_z0(rx0,
269
       const float z1 = calc_z0(rx0,
270
                                mesh_index_to_xpos(cx), z_values[cx][cy],
270
                                mesh_index_to_xpos(cx), z_values[cx][cy],
271
-                               mesh_index_to_xpos(cx + 1), z_values[MIN(cx, GRID_MAX_POINTS_X - 2) + 1][cy]);
271
+                               mesh_index_to_xpos(cx + 1), z_values[_MIN(cx, GRID_MAX_POINTS_X - 2) + 1][cy]);
272
 
272
 
273
       const float z2 = calc_z0(rx0,
273
       const float z2 = calc_z0(rx0,
274
-                               mesh_index_to_xpos(cx), z_values[cx][MIN(cy, GRID_MAX_POINTS_Y - 2) + 1],
275
-                               mesh_index_to_xpos(cx + 1), z_values[MIN(cx, GRID_MAX_POINTS_X - 2) + 1][MIN(cy, GRID_MAX_POINTS_Y - 2) + 1]);
274
+                               mesh_index_to_xpos(cx), z_values[cx][_MIN(cy, GRID_MAX_POINTS_Y - 2) + 1],
275
+                               mesh_index_to_xpos(cx + 1), z_values[_MIN(cx, GRID_MAX_POINTS_X - 2) + 1][_MIN(cy, GRID_MAX_POINTS_Y - 2) + 1]);
276
 
276
 
277
       float z0 = calc_z0(ry0,
277
       float z0 = calc_z0(ry0,
278
                          mesh_index_to_ypos(cy), z1,
278
                          mesh_index_to_ypos(cy), z1,

+ 6
- 6
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp View File

855
       save_ubl_active_state_and_disable();   // Disable bed level correction for probing
855
       save_ubl_active_state_and_disable();   // Disable bed level correction for probing
856
 
856
 
857
       do_blocking_move_to(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)), in_height);
857
       do_blocking_move_to(0.5f * (MESH_MAX_X - (MESH_MIN_X)), 0.5f * (MESH_MAX_Y - (MESH_MIN_Y)), in_height);
858
-        //, MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) * 0.5f);
858
+        //, _MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]) * 0.5f);
859
       planner.synchronize();
859
       planner.synchronize();
860
 
860
 
861
       SERIAL_ECHOPGM("Place shim under nozzle");
861
       SERIAL_ECHOPGM("Place shim under nozzle");
1385
     #include "../../../libs/vector_3.h"
1385
     #include "../../../libs/vector_3.h"
1386
 
1386
 
1387
     void unified_bed_leveling::tilt_mesh_based_on_probed_grid(const bool do_3_pt_leveling) {
1387
     void unified_bed_leveling::tilt_mesh_based_on_probed_grid(const bool do_3_pt_leveling) {
1388
-      constexpr int16_t x_min = MAX(MIN_PROBE_X, MESH_MIN_X),
1389
-                        x_max = MIN(MAX_PROBE_X, MESH_MAX_X),
1390
-                        y_min = MAX(MIN_PROBE_Y, MESH_MIN_Y),
1391
-                        y_max = MIN(MAX_PROBE_Y, MESH_MAX_Y);
1388
+      constexpr int16_t x_min = _MAX(MIN_PROBE_X, MESH_MIN_X),
1389
+                        x_max = _MIN(MAX_PROBE_X, MESH_MAX_X),
1390
+                        y_min = _MAX(MIN_PROBE_Y, MESH_MIN_Y),
1391
+                        y_max = _MIN(MAX_PROBE_Y, MESH_MAX_Y);
1392
 
1392
 
1393
       bool abort_flag = false;
1393
       bool abort_flag = false;
1394
 
1394
 
1654
 
1654
 
1655
       SERIAL_ECHOPGM("Extrapolating mesh...");
1655
       SERIAL_ECHOPGM("Extrapolating mesh...");
1656
 
1656
 
1657
-      const float weight_scaled = weight_factor * MAX(MESH_X_DIST, MESH_Y_DIST);
1657
+      const float weight_scaled = weight_factor * _MAX(MESH_X_DIST, MESH_Y_DIST);
1658
 
1658
 
1659
       for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++)
1659
       for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++)
1660
         for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++)
1660
         for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++)

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

40
 bool BLTouch::command(const BLTCommand cmd, const millis_t &ms) {
40
 bool BLTouch::command(const BLTCommand cmd, const millis_t &ms) {
41
   if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("BLTouch Command :", cmd);
41
   if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("BLTouch Command :", cmd);
42
   MOVE_SERVO(Z_PROBE_SERVO_NR, cmd);
42
   MOVE_SERVO(Z_PROBE_SERVO_NR, cmd);
43
-  safe_delay(MAX(ms, (uint32_t)BLTOUCH_DELAY)); // BLTOUCH_DELAY is also the *minimum* delay
43
+  safe_delay(_MAX(ms, (uint32_t)BLTOUCH_DELAY)); // BLTOUCH_DELAY is also the *minimum* delay
44
   return triggered();
44
   return triggered();
45
 }
45
 }
46
 
46
 

+ 1
- 1
Marlin/src/feature/dac/dac_mcp4728.cpp View File

108
 uint16_t mcp4728_getVout(const uint8_t channel) {
108
 uint16_t mcp4728_getVout(const uint8_t channel) {
109
   const uint32_t vref = 2048,
109
   const uint32_t vref = 2048,
110
                  vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
110
                  vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
111
-  return MIN(vOut, defaultVDD);
111
+  return _MIN(vOut, defaultVDD);
112
 }
112
 }
113
 #endif
113
 #endif
114
 
114
 

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

87
 
87
 
88
 // This is for the MCP4018 I2C based digipot
88
 // This is for the MCP4018 I2C based digipot
89
 void digipot_i2c_set_current(const uint8_t channel, const float current) {
89
 void digipot_i2c_set_current(const uint8_t channel, const float current) {
90
-  i2c_send(channel, current_to_wiper(MIN(MAX(current, 0), float(DIGIPOT_A4988_MAX_CURRENT))));
90
+  i2c_send(channel, current_to_wiper(_MIN(_MAX(current, 0), float(DIGIPOT_A4988_MAX_CURRENT))));
91
 }
91
 }
92
 
92
 
93
 void digipot_i2c_init() {
93
 void digipot_i2c_init() {

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

72
 
72
 
73
   // Set actual wiper value
73
   // Set actual wiper value
74
   byte addresses[4] = { 0x00, 0x10, 0x60, 0x70 };
74
   byte addresses[4] = { 0x00, 0x10, 0x60, 0x70 };
75
-  i2c_send(addr, addresses[channel & 0x3], current_to_wiper(MIN((float) MAX(current, 0), DIGIPOT_I2C_MAX_CURRENT)));
75
+  i2c_send(addr, addresses[channel & 0x3], current_to_wiper(MIN((float) _MAX(current, 0), DIGIPOT_I2C_MAX_CURRENT)));
76
 }
76
 }
77
 
77
 
78
 void digipot_i2c_init() {
78
 void digipot_i2c_init() {

+ 2
- 2
Marlin/src/feature/leds/tempstat.cpp View File

38
     next_status_led_update_ms += 500; // Update every 0.5s
38
     next_status_led_update_ms += 500; // Update every 0.5s
39
     float max_temp = 0.0;
39
     float max_temp = 0.0;
40
     #if HAS_HEATED_BED
40
     #if HAS_HEATED_BED
41
-      max_temp = MAX(thermalManager.degTargetBed(), thermalManager.degBed());
41
+      max_temp = _MAX(thermalManager.degTargetBed(), thermalManager.degBed());
42
     #endif
42
     #endif
43
     HOTEND_LOOP()
43
     HOTEND_LOOP()
44
-      max_temp = MAX(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e));
44
+      max_temp = _MAX(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e));
45
     const int8_t new_red = (max_temp > 55.0) ? HIGH : (max_temp < 54.0 || old_red < 0) ? LOW : old_red;
45
     const int8_t new_red = (max_temp > 55.0) ? HIGH : (max_temp < 54.0 || old_red < 0) ? LOW : old_red;
46
     if (new_red != old_red) {
46
     if (new_red != old_red) {
47
       old_red = new_red;
47
       old_red = new_red;

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

136
   float csum = 0, cmax = 0;
136
   float csum = 0, cmax = 0;
137
   MIXER_STEPPER_LOOP(i) {
137
   MIXER_STEPPER_LOOP(i) {
138
     const float v = color[t][i];
138
     const float v = color[t][i];
139
-    cmax = MAX(cmax, v);
139
+    cmax = _MAX(cmax, v);
140
     csum += v;
140
     csum += v;
141
   }
141
   }
142
   //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", int(t), ") cmax=", cmax, "  csum=", csum, "  color");
142
   //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", int(t), ") cmax=", cmax, "  csum=", csum, "  color");

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

103
   static void refresh_collector(const float proportion=1.0, const uint8_t t=selected_vtool, float (&c)[MIXING_STEPPERS]=collector);
103
   static void refresh_collector(const float proportion=1.0, const uint8_t t=selected_vtool, float (&c)[MIXING_STEPPERS]=collector);
104
 
104
 
105
   // Used up to Planner level
105
   // Used up to Planner level
106
-  FORCE_INLINE static void set_collector(const uint8_t c, const float f) { collector[c] = MAX(f, 0.0f); }
106
+  FORCE_INLINE static void set_collector(const uint8_t c, const float f) { collector[c] = _MAX(f, 0.0f); }
107
 
107
 
108
   static void normalize(const uint8_t tool_index);
108
   static void normalize(const uint8_t tool_index);
109
   FORCE_INLINE static void normalize() { normalize(selected_vtool); }
109
   FORCE_INLINE static void normalize() { normalize(selected_vtool); }
142
     static inline void copy_mix_to_color(mixer_comp_t (&tcolor)[MIXING_STEPPERS]) {
142
     static inline void copy_mix_to_color(mixer_comp_t (&tcolor)[MIXING_STEPPERS]) {
143
       // Scale each component to the largest one in terms of COLOR_A_MASK
143
       // Scale each component to the largest one in terms of COLOR_A_MASK
144
       // So the largest component will be COLOR_A_MASK and the other will be in proportion to it
144
       // So the largest component will be COLOR_A_MASK and the other will be in proportion to it
145
-      const float scale = (COLOR_A_MASK) * RECIPROCAL(float(MAX(mix[0], mix[1])));
145
+      const float scale = (COLOR_A_MASK) * RECIPROCAL(float(_MAX(mix[0], mix[1])));
146
 
146
 
147
       // Scale all values so their maximum is COLOR_A_MASK
147
       // Scale all values so their maximum is COLOR_A_MASK
148
       MIXER_STEPPER_LOOP(i) tcolor[i] = mix[i] * scale;
148
       MIXER_STEPPER_LOOP(i) tcolor[i] = mix[i] * scale;

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

394
 
394
 
395
       if (parser.seen('H')) {
395
       if (parser.seen('H')) {
396
         const int16_t size = (int16_t)parser.value_linear_units();
396
         const int16_t size = (int16_t)parser.value_linear_units();
397
-        left_probe_bed_position  = MAX(X_CENTER - size / 2, MIN_PROBE_X);
398
-        right_probe_bed_position = MIN(left_probe_bed_position + size, MAX_PROBE_X);
399
-        front_probe_bed_position = MAX(Y_CENTER - size / 2, MIN_PROBE_Y);
400
-        back_probe_bed_position  = MIN(front_probe_bed_position + size, MAX_PROBE_Y);
397
+        left_probe_bed_position  = _MAX(X_CENTER - size / 2, MIN_PROBE_X);
398
+        right_probe_bed_position = _MIN(left_probe_bed_position + size, MAX_PROBE_X);
399
+        front_probe_bed_position = _MAX(Y_CENTER - size / 2, MIN_PROBE_Y);
400
+        back_probe_bed_position  = _MIN(front_probe_bed_position + size, MAX_PROBE_Y);
401
       }
401
       }
402
       else {
402
       else {
403
         left_probe_bed_position  = parser.seenval('L') ? (int)RAW_X_POSITION(parser.value_linear_units()) : LEFT_PROBE_BED_POSITION;
403
         left_probe_bed_position  = parser.seenval('L') ? (int)RAW_X_POSITION(parser.value_linear_units()) : LEFT_PROBE_BED_POSITION;
511
     if (verbose_level || seenQ) {
511
     if (verbose_level || seenQ) {
512
       SERIAL_ECHOPGM("Manual G29 ");
512
       SERIAL_ECHOPGM("Manual G29 ");
513
       if (g29_in_progress) {
513
       if (g29_in_progress) {
514
-        SERIAL_ECHOPAIR("point ", MIN(abl_probe_index + 1, abl_points));
514
+        SERIAL_ECHOPAIR("point ", _MIN(abl_probe_index + 1, abl_points));
515
         SERIAL_ECHOLNPAIR(" of ", abl_points);
515
         SERIAL_ECHOLNPAIR(" of ", abl_points);
516
       }
516
       }
517
       else
517
       else

+ 1
- 1
Marlin/src/gcode/bedlevel/mbl/G29.cpp View File

197
   } // switch(state)
197
   } // switch(state)
198
 
198
 
199
   if (state == MeshNext) {
199
   if (state == MeshNext) {
200
-    SERIAL_ECHOPAIR("MBL G29 point ", MIN(mbl_probe_index, GRID_MAX_POINTS));
200
+    SERIAL_ECHOPAIR("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS));
201
     SERIAL_ECHOLNPAIR(" of ", int(GRID_MAX_POINTS));
201
     SERIAL_ECHOLNPAIR(" of ", int(GRID_MAX_POINTS));
202
   }
202
   }
203
 
203
 

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

75
     const float mlx = max_length(X_AXIS),
75
     const float mlx = max_length(X_AXIS),
76
                 mly = max_length(Y_AXIS),
76
                 mly = max_length(Y_AXIS),
77
                 mlratio = mlx > mly ? mly / mlx : mlx / mly,
77
                 mlratio = mlx > mly ? mly / mlx : mlx / mly,
78
-                fr_mm_s = MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0);
78
+                fr_mm_s = _MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0);
79
 
79
 
80
     #if ENABLED(SENSORLESS_HOMING)
80
     #if ENABLED(SENSORLESS_HOMING)
81
       sensorless_t stealth_states { false, false, false, false, false, false, false };
81
       sensorless_t stealth_states { false, false, false, false, false, false, false };

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

610
       }
610
       }
611
 
611
 
612
       // adjust delta_height and endstops by the max amount
612
       // adjust delta_height and endstops by the max amount
613
-      const float z_temp = MAX(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
613
+      const float z_temp = _MAX(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
614
       delta_height -= z_temp;
614
       delta_height -= z_temp;
615
       LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp;
615
       LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp;
616
     }
616
     }

+ 6
- 6
Marlin/src/gcode/calibrate/G34_M422.cpp View File

123
 
123
 
124
     float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * (
124
     float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * (
125
       #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
125
       #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
126
-         SQRT(MAX(HYPOT2(z_auto_align_xpos[0] - z_auto_align_ypos[0], z_auto_align_xpos[1] - z_auto_align_ypos[1]),
126
+         SQRT(_MAX(HYPOT2(z_auto_align_xpos[0] - z_auto_align_ypos[0], z_auto_align_xpos[1] - z_auto_align_ypos[1]),
127
                   HYPOT2(z_auto_align_xpos[1] - z_auto_align_ypos[1], z_auto_align_xpos[2] - z_auto_align_ypos[2]),
127
                   HYPOT2(z_auto_align_xpos[1] - z_auto_align_ypos[1], z_auto_align_xpos[2] - z_auto_align_ypos[2]),
128
                   HYPOT2(z_auto_align_xpos[2] - z_auto_align_ypos[2], z_auto_align_xpos[0] - z_auto_align_ypos[0])))
128
                   HYPOT2(z_auto_align_xpos[2] - z_auto_align_ypos[2], z_auto_align_xpos[0] - z_auto_align_ypos[0])))
129
       #else
129
       #else
174
         if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " measured position is ", z_measured[zstepper]);
174
         if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " measured position is ", z_measured[zstepper]);
175
 
175
 
176
         // Remember the minimum measurement to calculate the correction later on
176
         // Remember the minimum measurement to calculate the correction later on
177
-        z_measured_min = MIN(z_measured_min, z_measured[zstepper]);
177
+        z_measured_min = _MIN(z_measured_min, z_measured[zstepper]);
178
       } // for (zstepper)
178
       } // for (zstepper)
179
 
179
 
180
       if (err_break) break;
180
       if (err_break) break;
182
       // Adapt the next probe clearance height based on the new measurements.
182
       // Adapt the next probe clearance height based on the new measurements.
183
       // Safe_height = lowest distance to bed (= highest measurement) plus highest measured misalignment.
183
       // Safe_height = lowest distance to bed (= highest measurement) plus highest measured misalignment.
184
       #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
184
       #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
185
-        z_maxdiff = MAX(ABS(z_measured[0] - z_measured[1]), ABS(z_measured[1] - z_measured[2]), ABS(z_measured[2] - z_measured[0]));
186
-        z_probe = Z_BASIC_CLEARANCE + MAX(z_measured[0], z_measured[1], z_measured[2]) + z_maxdiff;
185
+        z_maxdiff = _MAX(ABS(z_measured[0] - z_measured[1]), ABS(z_measured[1] - z_measured[2]), ABS(z_measured[2] - z_measured[0]));
186
+        z_probe = Z_BASIC_CLEARANCE + _MAX(z_measured[0], z_measured[1], z_measured[2]) + z_maxdiff;
187
       #else
187
       #else
188
         z_maxdiff = ABS(z_measured[0] - z_measured[1]);
188
         z_maxdiff = ABS(z_measured[0] - z_measured[1]);
189
-        z_probe = Z_BASIC_CLEARANCE + MAX(z_measured[0], z_measured[1]) + z_maxdiff;
189
+        z_probe = Z_BASIC_CLEARANCE + _MAX(z_measured[0], z_measured[1]) + z_maxdiff;
190
       #endif
190
       #endif
191
 
191
 
192
       SERIAL_ECHOPAIR("\n"
192
       SERIAL_ECHOPAIR("\n"
210
                     z_align_abs = ABS(z_align_move);
210
                     z_align_abs = ABS(z_align_move);
211
 
211
 
212
         // Optimize one iterations correction based on the first measurements
212
         // Optimize one iterations correction based on the first measurements
213
-        if (z_align_abs > 0.0f) amplification = iteration == 1 ? MIN(last_z_align_move[zstepper] / z_align_abs, 2.0f) : z_auto_align_amplification;
213
+        if (z_align_abs > 0.0f) amplification = iteration == 1 ? _MIN(last_z_align_move[zstepper] / z_align_abs, 2.0f) : z_auto_align_amplification;
214
 
214
 
215
         // Check for less accuracy compared to last move
215
         // Check for less accuracy compared to last move
216
         if (last_z_align_move[zstepper] < z_align_abs - 1.0) {
216
         if (last_z_align_move[zstepper] < z_align_abs - 1.0) {

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

120
   if (a3 != NO_AXIS) destination[a3] = p3;
120
   if (a3 != NO_AXIS) destination[a3] = p3;
121
 
121
 
122
   // Make sure coordinates are within bounds
122
   // Make sure coordinates are within bounds
123
-  destination[X_AXIS] = MAX(MIN(destination[X_AXIS], X_MAX_POS), X_MIN_POS);
124
-  destination[Y_AXIS] = MAX(MIN(destination[Y_AXIS], Y_MAX_POS), Y_MIN_POS);
125
-  destination[Z_AXIS] = MAX(MIN(destination[Z_AXIS], Z_MAX_POS), Z_MIN_POS);
123
+  destination[X_AXIS] = _MAX(_MIN(destination[X_AXIS], X_MAX_POS), X_MIN_POS);
124
+  destination[Y_AXIS] = _MAX(_MIN(destination[Y_AXIS], Y_MAX_POS), Y_MIN_POS);
125
+  destination[Z_AXIS] = _MAX(_MIN(destination[Z_AXIS], Z_MAX_POS), Z_MIN_POS);
126
 
126
 
127
   // Move to position
127
   // Move to position
128
   do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
128
   do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));

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

127
             (int) (0.1250000000 * (DELTA_PRINTABLE_RADIUS)),
127
             (int) (0.1250000000 * (DELTA_PRINTABLE_RADIUS)),
128
             (int) (0.3333333333 * (DELTA_PRINTABLE_RADIUS))
128
             (int) (0.3333333333 * (DELTA_PRINTABLE_RADIUS))
129
           #else
129
           #else
130
-            (int) 5.0, (int) (0.125 * MIN(X_BED_SIZE, Y_BED_SIZE))
130
+            (int) 5.0, (int) (0.125 * _MIN(X_BED_SIZE, Y_BED_SIZE))
131
           #endif
131
           #endif
132
         );
132
         );
133
 
133
 

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

92
         case DXC_AUTO_PARK_MODE:
92
         case DXC_AUTO_PARK_MODE:
93
           break;
93
           break;
94
         case DXC_DUPLICATION_MODE:
94
         case DXC_DUPLICATION_MODE:
95
-          if (parser.seen('X')) duplicate_extruder_x_offset = MAX(parser.value_linear_units(), X2_MIN_POS - x_home_pos(0));
95
+          if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), X2_MIN_POS - x_home_pos(0));
96
           if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff();
96
           if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff();
97
           if (active_extruder != 0) tool_change(0);
97
           if (active_extruder != 0) tool_change(0);
98
           break;
98
           break;

+ 4
- 4
Marlin/src/gcode/feature/pause/M701_M702.cpp View File

97
 
97
 
98
   // Lift Z axis
98
   // Lift Z axis
99
   if (park_point.z > 0)
99
   if (park_point.z > 0)
100
-    do_blocking_move_to_z(MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE);
100
+    do_blocking_move_to_z(_MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE);
101
 
101
 
102
   // Load filament
102
   // Load filament
103
   #if ENABLED(PRUSA_MMU2)
103
   #if ENABLED(PRUSA_MMU2)
116
 
116
 
117
   // Restore Z axis
117
   // Restore Z axis
118
   if (park_point.z > 0)
118
   if (park_point.z > 0)
119
-    do_blocking_move_to_z(MAX(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE);
119
+    do_blocking_move_to_z(_MAX(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE);
120
 
120
 
121
   #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2)
121
   #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2)
122
     // Restore toolhead if it was changed
122
     // Restore toolhead if it was changed
196
 
196
 
197
   // Lift Z axis
197
   // Lift Z axis
198
   if (park_point.z > 0)
198
   if (park_point.z > 0)
199
-    do_blocking_move_to_z(MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE);
199
+    do_blocking_move_to_z(_MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE);
200
 
200
 
201
   // Unload filament
201
   // Unload filament
202
   #if ENABLED(PRUSA_MMU2)
202
   #if ENABLED(PRUSA_MMU2)
226
 
226
 
227
   // Restore Z axis
227
   // Restore Z axis
228
   if (park_point.z > 0)
228
   if (park_point.z > 0)
229
-    do_blocking_move_to_z(MAX(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE);
229
+    do_blocking_move_to_z(_MAX(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE);
230
 
230
 
231
   #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2)
231
   #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2)
232
     // Restore toolhead if it was changed
232
     // Restore toolhead if it was changed

+ 1
- 1
Marlin/src/gcode/feature/trinamic/M122.cpp View File

41
     #if ENABLED(MONITOR_DRIVER_STATUS)
41
     #if ENABLED(MONITOR_DRIVER_STATUS)
42
       const bool sflag = parser.seen('S'), s0 = sflag && !parser.value_bool();
42
       const bool sflag = parser.seen('S'), s0 = sflag && !parser.value_bool();
43
       if (sflag) tmc_set_report_interval(s0 ? 0 : MONITOR_DRIVER_STATUS_INTERVAL_MS);
43
       if (sflag) tmc_set_report_interval(s0 ? 0 : MONITOR_DRIVER_STATUS_INTERVAL_MS);
44
-      if (!s0 && parser.seenval('P')) tmc_set_report_interval(MIN(parser.value_ushort(), MONITOR_DRIVER_STATUS_INTERVAL_MS));
44
+      if (!s0 && parser.seenval('P')) tmc_set_report_interval(_MIN(parser.value_ushort(), MONITOR_DRIVER_STATUS_INTERVAL_MS));
45
     #endif
45
     #endif
46
 
46
 
47
     if (parser.seen('V'))
47
     if (parser.seen('V'))

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

32
   #define _ALT_P active_extruder
32
   #define _ALT_P active_extruder
33
   #define _CNT_P EXTRUDERS
33
   #define _CNT_P EXTRUDERS
34
 #else
34
 #else
35
-  #define _ALT_P MIN(active_extruder, FAN_COUNT - 1)
35
+  #define _ALT_P _MIN(active_extruder, FAN_COUNT - 1)
36
   #define _CNT_P FAN_COUNT
36
   #define _CNT_P FAN_COUNT
37
 #endif
37
 #endif
38
 
38
 

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

1360
   #define _PROBE_RADIUS (DELTA_PRINTABLE_RADIUS - (MIN_PROBE_EDGE))
1360
   #define _PROBE_RADIUS (DELTA_PRINTABLE_RADIUS - (MIN_PROBE_EDGE))
1361
   #ifndef DELTA_CALIBRATION_RADIUS
1361
   #ifndef DELTA_CALIBRATION_RADIUS
1362
     #ifdef X_PROBE_OFFSET_FROM_EXTRUDER
1362
     #ifdef X_PROBE_OFFSET_FROM_EXTRUDER
1363
-      #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - MAX(ABS(X_PROBE_OFFSET_FROM_EXTRUDER), ABS(Y_PROBE_OFFSET_FROM_EXTRUDER), ABS(MIN_PROBE_EDGE)))
1363
+      #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - _MAX(ABS(X_PROBE_OFFSET_FROM_EXTRUDER), ABS(Y_PROBE_OFFSET_FROM_EXTRUDER), ABS(MIN_PROBE_EDGE)))
1364
     #else
1364
     #else
1365
       #define DELTA_CALIBRATION_RADIUS _PROBE_RADIUS
1365
       #define DELTA_CALIBRATION_RADIUS _PROBE_RADIUS
1366
     #endif
1366
     #endif
1398
 #else
1398
 #else
1399
 
1399
 
1400
   // Boundaries for Cartesian probing based on bed limits
1400
   // Boundaries for Cartesian probing based on bed limits
1401
-  #define _MIN_PROBE_X (MAX(X_MIN_BED + MIN_PROBE_EDGE, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1402
-  #define _MIN_PROBE_Y (MAX(Y_MIN_BED + MIN_PROBE_EDGE, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1403
-  #define _MAX_PROBE_X (MIN(X_MAX_BED - (MIN_PROBE_EDGE), X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1404
-  #define _MAX_PROBE_Y (MIN(Y_MAX_BED - (MIN_PROBE_EDGE), Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1401
+  #define _MIN_PROBE_X (_MAX(X_MIN_BED + MIN_PROBE_EDGE, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1402
+  #define _MIN_PROBE_Y (_MAX(Y_MIN_BED + MIN_PROBE_EDGE, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1403
+  #define _MAX_PROBE_X (_MIN(X_MAX_BED - (MIN_PROBE_EDGE), X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1404
+  #define _MAX_PROBE_Y (_MIN(Y_MAX_BED - (MIN_PROBE_EDGE), Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1405
 
1405
 
1406
 #endif
1406
 #endif
1407
 
1407
 
1438
   #else
1438
   #else
1439
     // Boundaries for Cartesian probing based on set limits
1439
     // Boundaries for Cartesian probing based on set limits
1440
     #if ENABLED(AUTO_BED_LEVELING_UBL)
1440
     #if ENABLED(AUTO_BED_LEVELING_UBL)
1441
-      #define _MESH_MIN_X (MAX(X_MIN_BED + MESH_INSET, X_MIN_POS))  // UBL is careful not to probe off the bed.  It does not
1442
-      #define _MESH_MIN_Y (MAX(Y_MIN_BED + MESH_INSET, Y_MIN_POS))  // need *_PROBE_OFFSET_FROM_EXTRUDER in the mesh dimensions
1443
-      #define _MESH_MAX_X (MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS))
1444
-      #define _MESH_MAX_Y (MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS))
1441
+      #define _MESH_MIN_X (_MAX(X_MIN_BED + MESH_INSET, X_MIN_POS))  // UBL is careful not to probe off the bed.  It does not
1442
+      #define _MESH_MIN_Y (_MAX(Y_MIN_BED + MESH_INSET, Y_MIN_POS))  // need *_PROBE_OFFSET_FROM_EXTRUDER in the mesh dimensions
1443
+      #define _MESH_MAX_X (_MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS))
1444
+      #define _MESH_MAX_Y (_MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS))
1445
     #else
1445
     #else
1446
-      #define _MESH_MIN_X (MAX(X_MIN_BED + MESH_INSET, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1447
-      #define _MESH_MIN_Y (MAX(Y_MIN_BED + MESH_INSET, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1448
-      #define _MESH_MAX_X (MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1449
-      #define _MESH_MAX_Y (MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1446
+      #define _MESH_MIN_X (_MAX(X_MIN_BED + MESH_INSET, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1447
+      #define _MESH_MIN_Y (_MAX(Y_MIN_BED + MESH_INSET, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1448
+      #define _MESH_MAX_X (_MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
1449
+      #define _MESH_MAX_Y (_MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
1450
     #endif
1450
     #endif
1451
   #endif
1451
   #endif
1452
 
1452
 

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

2130
                 sanity_arr_2[] = DEFAULT_MAX_FEEDRATE,
2130
                 sanity_arr_2[] = DEFAULT_MAX_FEEDRATE,
2131
                 sanity_arr_3[] = DEFAULT_MAX_ACCELERATION;
2131
                 sanity_arr_3[] = DEFAULT_MAX_ACCELERATION;
2132
 
2132
 
2133
-#define _ARR_TEST(N,I) (sanity_arr_##N[MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0)
2133
+#define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0)
2134
 
2134
 
2135
 static_assert(COUNT(sanity_arr_1) >= XYZE, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
2135
 static_assert(COUNT(sanity_arr_1) >= XYZE, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
2136
 static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)");
2136
 static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements. (Did you forget to enable DISTINCT_E_FACTORS?)");

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

382
     }
382
     }
383
     else {
383
     else {
384
       PGM_P p = text;
384
       PGM_P p = text;
385
-      int dly = time / MAX(slen, 1);
385
+      int dly = time / _MAX(slen, 1);
386
       for (uint8_t i = 0; i <= slen; i++) {
386
       for (uint8_t i = 0; i <= slen; i++) {
387
 
387
 
388
         // Go to the correct place
388
         // Go to the correct place
1325
          */
1325
          */
1326
 
1326
 
1327
         clear_custom_char(&new_char);
1327
         clear_custom_char(&new_char);
1328
-        const uint8_t ypix = MIN(upper_left.y_pixel_offset + pixels_per_y_mesh_pnt, HD44780_CHAR_HEIGHT);
1328
+        const uint8_t ypix = _MIN(upper_left.y_pixel_offset + pixels_per_y_mesh_pnt, HD44780_CHAR_HEIGHT);
1329
         for (j = upper_left.y_pixel_offset; j < ypix; j++) {
1329
         for (j = upper_left.y_pixel_offset; j < ypix; j++) {
1330
           i = upper_left.x_pixel_mask;
1330
           i = upper_left.x_pixel_mask;
1331
           for (k = 0; k < pixels_per_x_mesh_pnt; k++) {
1331
           for (k = 0; k < pixels_per_x_mesh_pnt; k++) {

+ 1
- 1
Marlin/src/lcd/dogm/dogm_Statusscreen.h View File

1170
     #define STATUS_LOGO_X 0
1170
     #define STATUS_LOGO_X 0
1171
   #endif
1171
   #endif
1172
   #ifndef STATUS_LOGO_Y
1172
   #ifndef STATUS_LOGO_Y
1173
-    #define STATUS_LOGO_Y MIN(0, 10 - (STATUS_LOGO_HEIGHT) / 2)
1173
+    #define STATUS_LOGO_Y _MIN(0, 10 - (STATUS_LOGO_HEIGHT) / 2)
1174
   #endif
1174
   #endif
1175
   #ifndef STATUS_LOGO_HEIGHT
1175
   #ifndef STATUS_LOGO_HEIGHT
1176
     #define STATUS_LOGO_HEIGHT (sizeof(status_logo_bmp) / (STATUS_LOGO_BYTEWIDTH))
1176
     #define STATUS_LOGO_HEIGHT (sizeof(status_logo_bmp) / (STATUS_LOGO_BYTEWIDTH))

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

96
   #define CHAMBER_ALT() false
96
   #define CHAMBER_ALT() false
97
 #endif
97
 #endif
98
 
98
 
99
-#define MAX_HOTEND_DRAW MIN(HOTENDS, ((LCD_PIXEL_WIDTH - (STATUS_LOGO_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) / (STATUS_HEATERS_XSPACE)))
99
+#define MAX_HOTEND_DRAW _MIN(HOTENDS, ((LCD_PIXEL_WIDTH - (STATUS_LOGO_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) / (STATUS_HEATERS_XSPACE)))
100
 #define STATUS_HEATERS_BOT (STATUS_HEATERS_Y + STATUS_HEATERS_HEIGHT - 1)
100
 #define STATUS_HEATERS_BOT (STATUS_HEATERS_Y + STATUS_HEATERS_HEIGHT - 1)
101
 
101
 
102
 #if ENABLED(MARLIN_DEV_MODE)
102
 #if ENABLED(MARLIN_DEV_MODE)

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

169
                         text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
169
                         text_width_1 = (sizeof(STRING_SPLASH_LINE1) - 1) * (MENU_FONT_WIDTH),
170
                         text_width_2 = (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH);
170
                         text_width_2 = (sizeof(STRING_SPLASH_LINE2) - 1) * (MENU_FONT_WIDTH);
171
     #endif
171
     #endif
172
-    constexpr uint8_t text_max_width = MAX(text_width_1, text_width_2),
172
+    constexpr uint8_t text_max_width = _MAX(text_width_1, text_width_2),
173
                       rspace = width - (START_BMPWIDTH);
173
                       rspace = width - (START_BMPWIDTH);
174
 
174
 
175
     int8_t offx, offy, txt_base, txt_offx_1, txt_offx_2;
175
     int8_t offx, offy, txt_base, txt_offx_1, txt_offx_2;

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

99
 #endif
99
 #endif
100
 
100
 
101
 inline float clamp(const float value, const float minimum, const float maximum) {
101
 inline float clamp(const float value, const float minimum, const float maximum) {
102
-  return MAX(MIN(value, maximum), minimum);
102
+  return _MAX(_MIN(value, maximum), minimum);
103
 }
103
 }
104
 
104
 
105
 static struct {
105
 static struct {

+ 2
- 2
Marlin/src/lcd/extui_malyan_lcd.cpp View File

80
 // Everything written needs the high bit set.
80
 // Everything written needs the high bit set.
81
 void write_to_lcd_P(PGM_P const message) {
81
 void write_to_lcd_P(PGM_P const message) {
82
   char encoded_message[MAX_CURLY_COMMAND];
82
   char encoded_message[MAX_CURLY_COMMAND];
83
-  uint8_t message_length = MIN(strlen_P(message), sizeof(encoded_message));
83
+  uint8_t message_length = _MIN(strlen_P(message), sizeof(encoded_message));
84
 
84
 
85
   for (uint8_t i = 0; i < message_length; i++)
85
   for (uint8_t i = 0; i < message_length; i++)
86
     encoded_message[i] = pgm_read_byte(&message[i]) | 0x80;
86
     encoded_message[i] = pgm_read_byte(&message[i]) | 0x80;
90
 
90
 
91
 void write_to_lcd(const char * const message) {
91
 void write_to_lcd(const char * const message) {
92
   char encoded_message[MAX_CURLY_COMMAND];
92
   char encoded_message[MAX_CURLY_COMMAND];
93
-  const uint8_t message_length = MIN(strlen(message), sizeof(encoded_message));
93
+  const uint8_t message_length = _MIN(strlen(message), sizeof(encoded_message));
94
 
94
 
95
   for (uint8_t i = 0; i < message_length; i++)
95
   for (uint8_t i = 0; i < message_length; i++)
96
     encoded_message[i] = message[i] | 0x80;
96
     encoded_message[i] = message[i] | 0x80;

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

89
   // for (uint8_t n = 0; n < head_ind; ++n) {
89
   // for (uint8_t n = 0; n < head_ind; ++n) {
90
   //   const pos_t &p = maze_walls[n], &q = maze_walls[n + 1];
90
   //   const pos_t &p = maze_walls[n], &q = maze_walls[n + 1];
91
   //   if (p.x == q.x) {
91
   //   if (p.x == q.x) {
92
-  //     const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
92
+  //     const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y));
93
   //     if (PAGE_CONTAINS(y1, y2))
93
   //     if (PAGE_CONTAINS(y1, y2))
94
   //       u8g.drawVLine(GAMEX(p.x), y1, y2 - y1 + 1);
94
   //       u8g.drawVLine(GAMEX(p.x), y1, y2 - y1 + 1);
95
   //   }
95
   //   }
96
   //   else if (PAGE_CONTAINS(GAMEY(p.y), GAMEY(p.y))) {
96
   //   else if (PAGE_CONTAINS(GAMEY(p.y), GAMEY(p.y))) {
97
-  //     const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
97
+  //     const int8_t x1 = GAMEX(_MIN(p.x, q.x)), x2 = GAMEX(_MAX(p.x, q.x));
98
   //     u8g.drawHLine(x1, GAMEY(p.y), x2 - x1 + 1);
98
   //     u8g.drawHLine(x1, GAMEY(p.y), x2 - x1 + 1);
99
   //   }
99
   //   }
100
   // }
100
   // }

+ 12
- 12
Marlin/src/lcd/menu/game/snake.cpp View File

102
   for (uint8_t n = 0; n < head_ind; ++n) {
102
   for (uint8_t n = 0; n < head_ind; ++n) {
103
     pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
103
     pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
104
     if (p.x == q.x) {
104
     if (p.x == q.x) {
105
-      if ((foodx == p.x - 1 || foodx == p.x) && WITHIN(foody, MIN(p.y, q.y), MAX(p.y, q.y)))
105
+      if ((foodx == p.x - 1 || foodx == p.x) && WITHIN(foody, _MIN(p.y, q.y), _MAX(p.y, q.y)))
106
         return true;
106
         return true;
107
     }
107
     }
108
-    else if ((foody == p.y - 1 || foody == p.y) && WITHIN(foodx, MIN(p.x, q.x), MAX(p.x, q.x)))
108
+    else if ((foody == p.y - 1 || foody == p.y) && WITHIN(foodx, _MIN(p.x, q.x), _MAX(p.x, q.x)))
109
       return true;
109
       return true;
110
   }
110
   }
111
   return false;
111
   return false;
164
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
164
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
165
       if (p.x != q.x) {
165
       if (p.x != q.x) {
166
         // Crossing horizontal segment
166
         // Crossing horizontal segment
167
-        if (WITHIN(h1.x, MIN(p.x, q.x), MAX(p.x, q.x)) && (h1.y <= p.y) == (h2.y >= p.y)) return true;
167
+        if (WITHIN(h1.x, _MIN(p.x, q.x), _MAX(p.x, q.x)) && (h1.y <= p.y) == (h2.y >= p.y)) return true;
168
       } // Overlapping vertical segment
168
       } // Overlapping vertical segment
169
-      else if (h1.x == p.x && MIN(h1.y, h2.y) <= MAX(p.y, q.y) && MAX(h1.y, h2.y) >= MIN(p.y, q.y)) return true;
169
+      else if (h1.x == p.x && _MIN(h1.y, h2.y) <= _MAX(p.y, q.y) && _MAX(h1.y, h2.y) >= _MIN(p.y, q.y)) return true;
170
     }
170
     }
171
   }
171
   }
172
   else {
172
   else {
176
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
176
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
177
       if (p.y != q.y) {
177
       if (p.y != q.y) {
178
         // Crossing vertical segment
178
         // Crossing vertical segment
179
-        if (WITHIN(h1.y, MIN(p.y, q.y), MAX(p.y, q.y)) && (h1.x <= p.x) == (h2.x >= p.x)) return true;
179
+        if (WITHIN(h1.y, _MIN(p.y, q.y), _MAX(p.y, q.y)) && (h1.x <= p.x) == (h2.x >= p.x)) return true;
180
       } // Overlapping horizontal segment
180
       } // Overlapping horizontal segment
181
-      else if (h1.y == p.y && MIN(h1.x, h2.x) <= MAX(p.x, q.x) && MAX(h1.x, h2.x) >= MIN(p.x, q.x)) return true;
181
+      else if (h1.y == p.y && _MIN(h1.x, h2.x) <= _MAX(p.x, q.x) && _MAX(h1.x, h2.x) >= _MIN(p.x, q.x)) return true;
182
     }
182
     }
183
   }
183
   }
184
   return false;
184
   return false;
254
     for (uint8_t n = 0; n < head_ind; ++n) {
254
     for (uint8_t n = 0; n < head_ind; ++n) {
255
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
255
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
256
       if (p.x == q.x) {
256
       if (p.x == q.x) {
257
-        const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
257
+        const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y));
258
         if (PAGE_CONTAINS(y1, y2))
258
         if (PAGE_CONTAINS(y1, y2))
259
           u8g.drawVLine(GAMEX(p.x), y1, y2 - y1 + 1);
259
           u8g.drawVLine(GAMEX(p.x), y1, y2 - y1 + 1);
260
       }
260
       }
261
       else if (PAGE_CONTAINS(GAMEY(p.y), GAMEY(p.y))) {
261
       else if (PAGE_CONTAINS(GAMEY(p.y), GAMEY(p.y))) {
262
-        const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
262
+        const int8_t x1 = GAMEX(_MIN(p.x, q.x)), x2 = GAMEX(_MAX(p.x, q.x));
263
         u8g.drawHLine(x1, GAMEY(p.y), x2 - x1 + 1);
263
         u8g.drawHLine(x1, GAMEY(p.y), x2 - x1 + 1);
264
       }
264
       }
265
     }
265
     }
270
     for (uint8_t n = 0; n < head_ind; ++n) {
270
     for (uint8_t n = 0; n < head_ind; ++n) {
271
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
271
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
272
       if (p.x == q.x) {
272
       if (p.x == q.x) {
273
-        const int8_t y1 = GAMEY(MIN(p.y, q.y)), y2 = GAMEY(MAX(p.y, q.y));
273
+        const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y));
274
         if (PAGE_CONTAINS(y1, y2 + 1))
274
         if (PAGE_CONTAINS(y1, y2 + 1))
275
           u8g.drawFrame(GAMEX(p.x), y1, 2, y2 - y1 + 1 + 1);
275
           u8g.drawFrame(GAMEX(p.x), y1, 2, y2 - y1 + 1 + 1);
276
       }
276
       }
277
       else {
277
       else {
278
         const int8_t py = GAMEY(p.y);
278
         const int8_t py = GAMEY(p.y);
279
         if (PAGE_CONTAINS(py, py + 1)) {
279
         if (PAGE_CONTAINS(py, py + 1)) {
280
-          const int8_t x1 = GAMEX(MIN(p.x, q.x)), x2 = GAMEX(MAX(p.x, q.x));
280
+          const int8_t x1 = GAMEX(_MIN(p.x, q.x)), x2 = GAMEX(_MAX(p.x, q.x));
281
           u8g.drawFrame(x1, py, x2 - x1 + 1 + 1, 2);
281
           u8g.drawFrame(x1, py, x2 - x1 + 1 + 1, 2);
282
         }
282
         }
283
       }
283
       }
289
     for (uint8_t n = 0; n < head_ind; ++n) {
289
     for (uint8_t n = 0; n < head_ind; ++n) {
290
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
290
       const pos_t &p = snake_tail[n], &q = snake_tail[n + 1];
291
       if (p.x == q.x) {
291
       if (p.x == q.x) {
292
-        const int8_t y1 = MIN(p.y, q.y), y2 = MAX(p.y, q.y);
292
+        const int8_t y1 = _MIN(p.y, q.y), y2 = _MAX(p.y, q.y);
293
         if (PAGE_CONTAINS(GAMEY(y1), GAMEY(y2) + SNAKE_SIZ - 1)) {
293
         if (PAGE_CONTAINS(GAMEY(y1), GAMEY(y2) + SNAKE_SIZ - 1)) {
294
           for (int8_t i = y1; i <= y2; ++i) {
294
           for (int8_t i = y1; i <= y2; ++i) {
295
             const int8_t y = GAMEY(i);
295
             const int8_t y = GAMEY(i);
301
       else {
301
       else {
302
         const int8_t py = GAMEY(p.y);
302
         const int8_t py = GAMEY(p.y);
303
         if (PAGE_CONTAINS(py, py + SNAKE_SIZ - 1)) {
303
         if (PAGE_CONTAINS(py, py + SNAKE_SIZ - 1)) {
304
-          const int8_t x1 = MIN(p.x, q.x), x2 = MAX(p.x, q.x);
304
+          const int8_t x1 = _MIN(p.x, q.x), x2 = _MAX(p.x, q.x);
305
           for (int8_t i = x1; i <= x2; ++i)
305
           for (int8_t i = x1; i <= x2; ++i)
306
             u8g.drawBox(GAMEX(i), py, SNAKE_SIZ, SNAKE_SIZ);
306
             u8g.drawBox(GAMEX(i), py, SNAKE_SIZ, SNAKE_SIZ);
307
         }
307
         }

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

326
     screen_changed = false;
326
     screen_changed = false;
327
   }
327
   }
328
   if (screen_items > 0 && encoderLine >= screen_items - limit) {
328
   if (screen_items > 0 && encoderLine >= screen_items - limit) {
329
-    encoderLine = MAX(0, screen_items - limit);
329
+    encoderLine = _MAX(0, screen_items - limit);
330
     ui.encoderPosition = encoderLine * (ENCODER_STEPS_PER_MENU_ITEM);
330
     ui.encoderPosition = encoderLine * (ENCODER_STEPS_PER_MENU_ITEM);
331
   }
331
   }
332
   if (is_menu) {
332
   if (is_menu) {

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

192
   public:
192
   public:
193
     static void action_edit(PGM_P const pstr, type_t * const ptr, const type_t minValue, const type_t maxValue, const screenFunc_t callback=nullptr, const bool live=false) {
193
     static void action_edit(PGM_P const pstr, type_t * const ptr, const type_t minValue, const type_t maxValue, const screenFunc_t callback=nullptr, const bool live=false) {
194
       // Make sure minv and maxv fit within int16_t
194
       // Make sure minv and maxv fit within int16_t
195
-      const int32_t minv = MAX(scale(minValue), INT_MIN),
196
-                    maxv = MIN(scale(maxValue), INT_MAX);
195
+      const int32_t minv = _MAX(scale(minValue), INT_MIN),
196
+                    maxv = _MIN(scale(maxValue), INT_MAX);
197
       init(pstr, ptr, minv, maxv - minv, scale(*ptr) - minv, edit, callback, live);
197
       init(pstr, ptr, minv, maxv - minv, scale(*ptr) - minv, edit, callback, live);
198
     }
198
     }
199
     static void edit() { MenuItemBase::edit(to_string, load); }
199
     static void edit() { MenuItemBase::edit(to_string, load); }

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

283
 
283
 
284
   void _menu_configuration_preheat_settings(const uint8_t material) {
284
   void _menu_configuration_preheat_settings(const uint8_t material) {
285
     #if HOTENDS > 5
285
     #if HOTENDS > 5
286
-      #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP, HEATER_5_MINTEMP)
287
-      #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP)
286
+      #define MINTEMP_ALL _MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP, HEATER_5_MINTEMP)
287
+      #define MAXTEMP_ALL _MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP)
288
     #elif HOTENDS > 4
288
     #elif HOTENDS > 4
289
-      #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP)
290
-      #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP)
289
+      #define MINTEMP_ALL _MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP)
290
+      #define MAXTEMP_ALL _MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP)
291
     #elif HOTENDS > 3
291
     #elif HOTENDS > 3
292
-      #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP)
293
-      #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP)
292
+      #define MINTEMP_ALL _MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP)
293
+      #define MAXTEMP_ALL _MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP)
294
     #elif HOTENDS > 2
294
     #elif HOTENDS > 2
295
-      #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP)
296
-      #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP)
295
+      #define MINTEMP_ALL _MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP)
296
+      #define MAXTEMP_ALL _MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP)
297
     #elif HOTENDS > 1
297
     #elif HOTENDS > 1
298
-      #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP)
299
-      #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP)
298
+      #define MINTEMP_ALL _MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP)
299
+      #define MAXTEMP_ALL _MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP)
300
     #else
300
     #else
301
       #define MINTEMP_ALL HEATER_0_MINTEMP
301
       #define MINTEMP_ALL HEATER_0_MINTEMP
302
       #define MAXTEMP_ALL HEATER_0_MAXTEMP
302
       #define MAXTEMP_ALL HEATER_0_MAXTEMP

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

39
 void _man_probe_pt(const float &rx, const float &ry) {
39
 void _man_probe_pt(const float &rx, const float &ry) {
40
   do_blocking_move_to(rx, ry, Z_CLEARANCE_BETWEEN_PROBES);
40
   do_blocking_move_to(rx, ry, Z_CLEARANCE_BETWEEN_PROBES);
41
   ui.synchronize();
41
   ui.synchronize();
42
-  move_menu_scale = MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / float(DEFAULT_XYZ_STEPS_PER_UNIT));
42
+  move_menu_scale = _MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / float(DEFAULT_XYZ_STEPS_PER_UNIT));
43
   ui.goto_screen(lcd_move_z);
43
   ui.goto_screen(lcd_move_z);
44
 }
44
 }
45
 
45
 

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

48
 //
48
 //
49
 
49
 
50
 void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const uint8_t fan) {
50
 void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const uint8_t fan) {
51
-  if (temph > 0) thermalManager.setTargetHotend(MIN(heater_maxtemp[endnum] - 15, temph), endnum);
51
+  if (temph > 0) thermalManager.setTargetHotend(_MIN(heater_maxtemp[endnum] - 15, temph), endnum);
52
   #if HAS_HEATED_BED
52
   #if HAS_HEATED_BED
53
     if (tempb >= 0) thermalManager.setTargetBed(tempb);
53
     if (tempb >= 0) thermalManager.setTargetBed(tempb);
54
   #else
54
   #else

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

150
             static uint8_t filename_scroll_hash;
150
             static uint8_t filename_scroll_hash;
151
             if (filename_scroll_hash != hash) {                              // If the hash changed...
151
             if (filename_scroll_hash != hash) {                              // If the hash changed...
152
               filename_scroll_hash = hash;                                   // Save the new hash
152
               filename_scroll_hash = hash;                                   // Save the new hash
153
-              filename_scroll_max = MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit
153
+              filename_scroll_max = _MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit
154
               filename_scroll_pos = 0;                                       // Reset scroll to the start
154
               filename_scroll_pos = 0;                                       // Reset scroll to the start
155
               lcd_status_update_delay = 8;                                   // Don't scroll right away
155
               lcd_status_update_delay = 8;                                   // Don't scroll right away
156
             }
156
             }

+ 1
- 1
Marlin/src/lcd/ultralcd.h View File

293
     #if HAS_PRINT_PROGRESS
293
     #if HAS_PRINT_PROGRESS
294
       #if ENABLED(LCD_SET_PROGRESS_MANUALLY)
294
       #if ENABLED(LCD_SET_PROGRESS_MANUALLY)
295
         static uint8_t progress_bar_percent;
295
         static uint8_t progress_bar_percent;
296
-        static void set_progress(const uint8_t progress) { progress_bar_percent = MIN(progress, 100); }
296
+        static void set_progress(const uint8_t progress) { progress_bar_percent = _MIN(progress, 100); }
297
       #endif
297
       #endif
298
       static uint8_t get_progress();
298
       static uint8_t get_progress();
299
     #else
299
     #else

+ 4
- 4
Marlin/src/libs/least_squares_fit.h View File

61
   lsf->xzbar += w * x * z;
61
   lsf->xzbar += w * x * z;
62
   lsf->yzbar += w * y * z;
62
   lsf->yzbar += w * y * z;
63
   lsf->N     += w;
63
   lsf->N     += w;
64
-  lsf->max_absx = MAX(ABS(w * x), lsf->max_absx);
65
-  lsf->max_absy = MAX(ABS(w * y), lsf->max_absy);
64
+  lsf->max_absx = _MAX(ABS(w * x), lsf->max_absx);
65
+  lsf->max_absy = _MAX(ABS(w * y), lsf->max_absy);
66
 }
66
 }
67
 
67
 
68
 void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) {
68
 void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) {
75
   lsf->xybar += x * y;
75
   lsf->xybar += x * y;
76
   lsf->xzbar += x * z;
76
   lsf->xzbar += x * z;
77
   lsf->yzbar += y * z;
77
   lsf->yzbar += y * z;
78
-  lsf->max_absx = MAX(ABS(x), lsf->max_absx);
79
-  lsf->max_absy = MAX(ABS(y), lsf->max_absy);
78
+  lsf->max_absx = _MAX(ABS(x), lsf->max_absx);
79
+  lsf->max_absy = _MAX(ABS(y), lsf->max_absy);
80
   lsf->N += 1.0;
80
   lsf->N += 1.0;
81
 }
81
 }
82
 
82
 

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

172
         break;
172
         break;
173
 
173
 
174
       case 2: // Raise by Z-park height
174
       case 2: // Raise by Z-park height
175
-        do_blocking_move_to_z(MIN(current_position[Z_AXIS] + park.z, Z_MAX_POS), fr_z);
175
+        do_blocking_move_to_z(_MIN(current_position[Z_AXIS] + park.z, Z_MAX_POS), fr_z);
176
         break;
176
         break;
177
 
177
 
178
       default: // Raise to at least the Z-park height
178
       default: // Raise to at least the Z-park height
179
-        do_blocking_move_to_z(MAX(park.z, current_position[Z_AXIS]), fr_z);
179
+        do_blocking_move_to_z(_MAX(park.z, current_position[Z_AXIS]), fr_z);
180
     }
180
     }
181
 
181
 
182
     do_blocking_move_to_xy(park.x, park.y, fr_xy);
182
     do_blocking_move_to_xy(park.x, park.y, fr_xy);

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

126
 typedef struct {     bool X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t;
126
 typedef struct {     bool X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t;
127
 
127
 
128
 // Limit an index to an array size
128
 // Limit an index to an array size
129
-#define ALIM(I,ARR) MIN(I, COUNT(ARR) - 1)
129
+#define ALIM(I,ARR) _MIN(I, COUNT(ARR) - 1)
130
 
130
 
131
 /**
131
 /**
132
  * Current EEPROM Layout
132
  * Current EEPROM Layout

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

125
     );
125
     );
126
     LOOP_XYZ(i) HOTEND_LOOP() hotend_offset[i][e] = tmp[i][e];
126
     LOOP_XYZ(i) HOTEND_LOOP() hotend_offset[i][e] = tmp[i][e];
127
     #if ENABLED(DUAL_X_CARRIAGE)
127
     #if ENABLED(DUAL_X_CARRIAGE)
128
-      hotend_offset[X_AXIS][1] = MAX(X2_HOME_POS, X2_MAX_POS);
128
+      hotend_offset[X_AXIS][1] = _MAX(X2_HOME_POS, X2_MAX_POS);
129
     #endif
129
     #endif
130
   }
130
   }
131
 #endif
131
 #endif
473
       if (axis == X_AXIS) {
473
       if (axis == X_AXIS) {
474
 
474
 
475
         // In Dual X mode hotend_offset[X] is T1's home position
475
         // In Dual X mode hotend_offset[X] is T1's home position
476
-        const float dual_max_x = MAX(hotend_offset[X_AXIS][1], X2_MAX_POS);
476
+        const float dual_max_x = _MAX(hotend_offset[X_AXIS][1], X2_MAX_POS);
477
 
477
 
478
         if (new_tool_index != 0) {
478
         if (new_tool_index != 0) {
479
           // T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger)
479
           // T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger)
484
           // In Duplication Mode, T0 can move as far left as X1_MIN_POS
484
           // In Duplication Mode, T0 can move as far left as X1_MIN_POS
485
           // but not so far to the right that T1 would move past the end
485
           // but not so far to the right that T1 would move past the end
486
           soft_endstop[X_AXIS].min = X1_MIN_POS;
486
           soft_endstop[X_AXIS].min = X1_MIN_POS;
487
-          soft_endstop[X_AXIS].max = MIN(X1_MAX_POS, dual_max_x - duplicate_extruder_x_offset);
487
+          soft_endstop[X_AXIS].max = _MIN(X1_MAX_POS, dual_max_x - duplicate_extruder_x_offset);
488
         }
488
         }
489
         else {
489
         else {
490
           // In other modes, T0 can move from X1_MIN_POS to X1_MAX_POS
490
           // In other modes, T0 can move from X1_MIN_POS to X1_MAX_POS
507
         case X_AXIS:
507
         case X_AXIS:
508
         case Y_AXIS:
508
         case Y_AXIS:
509
           // Get a minimum radius for clamping
509
           // Get a minimum radius for clamping
510
-          delta_max_radius = MIN(ABS(MAX(soft_endstop[X_AXIS].min, soft_endstop[Y_AXIS].min)), soft_endstop[X_AXIS].max, soft_endstop[Y_AXIS].max);
510
+          delta_max_radius = _MIN(ABS(_MAX(soft_endstop[X_AXIS].min, soft_endstop[Y_AXIS].min)), soft_endstop[X_AXIS].max, soft_endstop[Y_AXIS].max);
511
           delta_max_radius_2 = sq(delta_max_radius);
511
           delta_max_radius_2 = sq(delta_max_radius);
512
           break;
512
           break;
513
         case Z_AXIS:
513
         case Z_AXIS:
1441
   // When homing Z with probe respect probe clearance
1441
   // When homing Z with probe respect probe clearance
1442
   const float bump = axis_home_dir * (
1442
   const float bump = axis_home_dir * (
1443
     #if HOMING_Z_WITH_PROBE
1443
     #if HOMING_Z_WITH_PROBE
1444
-      (axis == Z_AXIS && (Z_HOME_BUMP_MM)) ? MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_HOME_BUMP_MM) :
1444
+      (axis == Z_AXIS && (Z_HOME_BUMP_MM)) ? _MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_HOME_BUMP_MM) :
1445
     #endif
1445
     #endif
1446
     home_bump_mm(axis)
1446
     home_bump_mm(axis)
1447
   );
1447
   );

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

733
   // reach the final_rate exactly at the end of this block.
733
   // reach the final_rate exactly at the end of this block.
734
   if (plateau_steps < 0) {
734
   if (plateau_steps < 0) {
735
     const float accelerate_steps_float = CEIL(intersection_distance(initial_rate, final_rate, accel, block->step_event_count));
735
     const float accelerate_steps_float = CEIL(intersection_distance(initial_rate, final_rate, accel, block->step_event_count));
736
-    accelerate_steps = MIN(uint32_t(MAX(accelerate_steps_float, 0)), block->step_event_count);
736
+    accelerate_steps = _MIN(uint32_t(_MAX(accelerate_steps_float, 0)), block->step_event_count);
737
     plateau_steps = 0;
737
     plateau_steps = 0;
738
 
738
 
739
     #if ENABLED(S_CURVE_ACCELERATION)
739
     #if ENABLED(S_CURVE_ACCELERATION)
855
 
855
 
856
       const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
856
       const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
857
         ? max_entry_speed_sqr
857
         ? max_entry_speed_sqr
858
-        : MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(float(MINIMUM_PLANNER_SPEED)), current->millimeters));
858
+        : _MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(float(MINIMUM_PLANNER_SPEED)), current->millimeters));
859
       if (current->entry_speed_sqr != new_entry_speed_sqr) {
859
       if (current->entry_speed_sqr != new_entry_speed_sqr) {
860
 
860
 
861
         // Need to recalculate the block speed - Mark it now, so the stepper
861
         // Need to recalculate the block speed - Mark it now, so the stepper
1817
   }
1817
   }
1818
 
1818
 
1819
   block->steps[E_AXIS] = esteps;
1819
   block->steps[E_AXIS] = esteps;
1820
-  block->step_event_count = MAX(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], esteps);
1820
+  block->step_event_count = _MAX(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], esteps);
1821
 
1821
 
1822
   // Bail if this is a zero-length block
1822
   // Bail if this is a zero-length block
1823
   if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false;
1823
   if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false;
2128
     }
2128
     }
2129
     ys0 = axis_segment_time_us[Y_AXIS][0] = ys0 + segment_time_us;
2129
     ys0 = axis_segment_time_us[Y_AXIS][0] = ys0 + segment_time_us;
2130
 
2130
 
2131
-    const uint32_t max_x_segment_time = MAX(xs0, xs1, xs2),
2132
-                   max_y_segment_time = MAX(ys0, ys1, ys2),
2133
-                   min_xy_segment_time = MIN(max_x_segment_time, max_y_segment_time);
2131
+    const uint32_t max_x_segment_time = _MAX(xs0, xs1, xs2),
2132
+                   max_y_segment_time = _MAX(ys0, ys1, ys2),
2133
+                   min_xy_segment_time = _MIN(max_x_segment_time, max_y_segment_time);
2134
     if (min_xy_segment_time < MAX_FREQ_TIME_US) {
2134
     if (min_xy_segment_time < MAX_FREQ_TIME_US) {
2135
       const float low_sf = speed_factor * min_xy_segment_time / (MAX_FREQ_TIME_US);
2135
       const float low_sf = speed_factor * min_xy_segment_time / (MAX_FREQ_TIME_US);
2136
       NOMORE(speed_factor, low_sf);
2136
       NOMORE(speed_factor, low_sf);
2370
       }
2370
       }
2371
 
2371
 
2372
       // Get the lowest speed
2372
       // Get the lowest speed
2373
-      vmax_junction_sqr = MIN(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr);
2373
+      vmax_junction_sqr = _MIN(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr);
2374
     }
2374
     }
2375
     else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later.
2375
     else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later.
2376
       vmax_junction_sqr = 0;
2376
       vmax_junction_sqr = 0;
2427
       // The junction velocity will be shared between successive segments. Limit the junction velocity to their minimum.
2427
       // The junction velocity will be shared between successive segments. Limit the junction velocity to their minimum.
2428
       // Pick the smaller of the nominal speeds. Higher speed shall not be achieved at the junction during coasting.
2428
       // Pick the smaller of the nominal speeds. Higher speed shall not be achieved at the junction during coasting.
2429
       const float previous_nominal_speed = SQRT(previous_nominal_speed_sqr);
2429
       const float previous_nominal_speed = SQRT(previous_nominal_speed_sqr);
2430
-      vmax_junction = MIN(nominal_speed, previous_nominal_speed);
2430
+      vmax_junction = _MIN(nominal_speed, previous_nominal_speed);
2431
 
2431
 
2432
       // Now limit the jerk in all axes.
2432
       // Now limit the jerk in all axes.
2433
       const float smaller_speed_factor = vmax_junction / previous_nominal_speed;
2433
       const float smaller_speed_factor = vmax_junction / previous_nominal_speed;
2448
         // Calculate jerk depending on whether the axis is coasting in the same direction or reversing.
2448
         // Calculate jerk depending on whether the axis is coasting in the same direction or reversing.
2449
         const float jerk = (v_exit > v_entry)
2449
         const float jerk = (v_exit > v_entry)
2450
             ? //                                  coasting             axis reversal
2450
             ? //                                  coasting             axis reversal
2451
-              ( (v_entry > 0 || v_exit < 0) ? (v_exit - v_entry) : MAX(v_exit, -v_entry) )
2451
+              ( (v_entry > 0 || v_exit < 0) ? (v_exit - v_entry) : _MAX(v_exit, -v_entry) )
2452
             : // v_exit <= v_entry                coasting             axis reversal
2452
             : // v_exit <= v_entry                coasting             axis reversal
2453
-              ( (v_entry < 0 || v_exit > 0) ? (v_entry - v_exit) : MAX(-v_exit, v_entry) );
2453
+              ( (v_entry < 0 || v_exit > 0) ? (v_entry - v_exit) : _MAX(-v_exit, v_entry) );
2454
 
2454
 
2455
         if (jerk > max_jerk[axis]) {
2455
         if (jerk > max_jerk[axis]) {
2456
           v_factor *= max_jerk[axis] / jerk;
2456
           v_factor *= max_jerk[axis] / jerk;
2470
     previous_safe_speed = safe_speed;
2470
     previous_safe_speed = safe_speed;
2471
 
2471
 
2472
     #if ENABLED(JUNCTION_DEVIATION)
2472
     #if ENABLED(JUNCTION_DEVIATION)
2473
-      vmax_junction_sqr = MIN(vmax_junction_sqr, sq(vmax_junction));
2473
+      vmax_junction_sqr = _MIN(vmax_junction_sqr, sq(vmax_junction));
2474
     #else
2474
     #else
2475
       vmax_junction_sqr = sq(vmax_junction);
2475
       vmax_junction_sqr = sq(vmax_junction);
2476
     #endif
2476
     #endif
2485
 
2485
 
2486
   // If we are trying to add a split block, start with the
2486
   // If we are trying to add a split block, start with the
2487
   // max. allowed speed to avoid an interrupted first move.
2487
   // max. allowed speed to avoid an interrupted first move.
2488
-  block->entry_speed_sqr = !split_move ? sq(float(MINIMUM_PLANNER_SPEED)) : MIN(vmax_junction_sqr, v_allowable_sqr);
2488
+  block->entry_speed_sqr = !split_move ? sq(float(MINIMUM_PLANNER_SPEED)) : _MIN(vmax_junction_sqr, v_allowable_sqr);
2489
 
2489
 
2490
   // Initialize planner efficiency flags
2490
   // Initialize planner efficiency flags
2491
   // Set flag if block will always reach maximum junction speed regardless of entry/exit speeds.
2491
   // Set flag if block will always reach maximum junction speed regardless of entry/exit speeds.

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

948
     #endif // JUNCTION_DEVIATION
948
     #endif // JUNCTION_DEVIATION
949
 };
949
 };
950
 
950
 
951
-#define PLANNER_XY_FEEDRATE() (MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]))
951
+#define PLANNER_XY_FEEDRATE() (_MIN(planner.settings.max_feedrate_mm_s[X_AXIS], planner.settings.max_feedrate_mm_s[Y_AXIS]))
952
 
952
 
953
 extern Planner planner;
953
 extern Planner planner;

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

246
     data.printTime += delta;
246
     data.printTime += delta;
247
 
247
 
248
     #if SERVICE_INTERVAL_1 > 0
248
     #if SERVICE_INTERVAL_1 > 0
249
-      data.nextService1 -= MIN(delta, data.nextService1);
249
+      data.nextService1 -= _MIN(delta, data.nextService1);
250
     #endif
250
     #endif
251
     #if SERVICE_INTERVAL_2 > 0
251
     #if SERVICE_INTERVAL_2 > 0
252
-      data.nextService2 -= MIN(delta, data.nextService2);
252
+      data.nextService2 -= _MIN(delta, data.nextService2);
253
     #endif
253
     #endif
254
     #if SERVICE_INTERVAL_3 > 0
254
     #if SERVICE_INTERVAL_3 > 0
255
-      data.nextService3 -= MIN(delta, data.nextService3);
255
+      data.nextService3 -= _MIN(delta, data.nextService3);
256
     #endif
256
     #endif
257
 
257
 
258
     update_next = now + updateInterval * 1000;
258
     update_next = now + updateInterval * 1000;

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

444
   #endif
444
   #endif
445
 
445
 
446
   if (deploy_stow_condition && unknown_condition)
446
   if (deploy_stow_condition && unknown_condition)
447
-    do_probe_raise(MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_CLEARANCE_DEPLOY_PROBE));
447
+    do_probe_raise(_MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_CLEARANCE_DEPLOY_PROBE));
448
 
448
 
449
   #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY)
449
   #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY)
450
     #if ENABLED(Z_PROBE_SLED)
450
     #if ENABLED(Z_PROBE_SLED)
780
   const float nz =
780
   const float nz =
781
     #if ENABLED(DELTA)
781
     #if ENABLED(DELTA)
782
       // Move below clip height or xy move will be aborted by do_blocking_move_to
782
       // Move below clip height or xy move will be aborted by do_blocking_move_to
783
-      MIN(current_position[Z_AXIS], delta_clip_start_height)
783
+      _MIN(current_position[Z_AXIS], delta_clip_start_height)
784
     #else
784
     #else
785
       current_position[Z_AXIS]
785
       current_position[Z_AXIS]
786
     #endif
786
     #endif

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

1291
 
1291
 
1292
     uint32_t interval =
1292
     uint32_t interval =
1293
       #if ENABLED(LIN_ADVANCE)
1293
       #if ENABLED(LIN_ADVANCE)
1294
-        MIN(nextAdvanceISR, nextMainISR)  // Nearest time interval
1294
+        _MIN(nextAdvanceISR, nextMainISR)  // Nearest time interval
1295
       #else
1295
       #else
1296
         nextMainISR                       // Remaining stepper ISR time
1296
         nextMainISR                       // Remaining stepper ISR time
1297
       #endif
1297
       #endif
1404
 
1404
 
1405
   // Count of pending loops and events for this iteration
1405
   // Count of pending loops and events for this iteration
1406
   const uint32_t pending_events = step_event_count - step_events_completed;
1406
   const uint32_t pending_events = step_event_count - step_events_completed;
1407
-  uint8_t events_to_do = MIN(pending_events, steps_per_isr);
1407
+  uint8_t events_to_do = _MIN(pending_events, steps_per_isr);
1408
 
1408
 
1409
   // Just update the value we will get at the end of the loop
1409
   // Just update the value we will get at the end of the loop
1410
   step_events_completed += events_to_do;
1410
   step_events_completed += events_to_do;

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

151
 #define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES)
151
 #define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES)
152
 
152
 
153
 // Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate
153
 // Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate
154
-#define _MIN_STEPPER_PULSE_CYCLES(N) MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N))
154
+#define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N))
155
 #if MINIMUM_STEPPER_PULSE
155
 #if MINIMUM_STEPPER_PULSE
156
   #define MIN_STEPPER_PULSE_CYCLES _MIN_STEPPER_PULSE_CYCLES(uint32_t(MINIMUM_STEPPER_PULSE))
156
   #define MIN_STEPPER_PULSE_CYCLES _MIN_STEPPER_PULSE_CYCLES(uint32_t(MINIMUM_STEPPER_PULSE))
157
 #elif HAS_DRIVER(LV8729)
157
 #elif HAS_DRIVER(LV8729)
174
 #define ADDED_STEP_TICKS (((MIN_STEPPER_PULSE_CYCLES) / (PULSE_TIMER_PRESCALE)) - (MIN_PULSE_TICKS))
174
 #define ADDED_STEP_TICKS (((MIN_STEPPER_PULSE_CYCLES) / (PULSE_TIMER_PRESCALE)) - (MIN_PULSE_TICKS))
175
 
175
 
176
 // But the user could be enforcing a minimum time, so the loop time is
176
 // But the user could be enforcing a minimum time, so the loop time is
177
-#define ISR_LOOP_CYCLES (ISR_LOOP_BASE_CYCLES + MAX(MIN_STEPPER_PULSE_CYCLES, MIN_ISR_LOOP_CYCLES))
177
+#define ISR_LOOP_CYCLES (ISR_LOOP_BASE_CYCLES + _MAX(MIN_STEPPER_PULSE_CYCLES, MIN_ISR_LOOP_CYCLES))
178
 
178
 
179
 // If linear advance is enabled, then it is handled separately
179
 // If linear advance is enabled, then it is handled separately
180
 #if ENABLED(LIN_ADVANCE)
180
 #if ENABLED(LIN_ADVANCE)
192
   #endif
192
   #endif
193
 
193
 
194
   // And the real loop time
194
   // And the real loop time
195
-  #define ISR_LA_LOOP_CYCLES MAX(MIN_STEPPER_PULSE_CYCLES, MIN_ISR_LA_LOOP_CYCLES)
195
+  #define ISR_LA_LOOP_CYCLES _MAX(MIN_STEPPER_PULSE_CYCLES, MIN_ISR_LA_LOOP_CYCLES)
196
 
196
 
197
 #else
197
 #else
198
   #define ISR_LA_LOOP_CYCLES 0UL
198
   #define ISR_LA_LOOP_CYCLES 0UL

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

143
           set_fan_speed(fan, new_fan_speed[fan]);
143
           set_fan_speed(fan, new_fan_speed[fan]);
144
           break;
144
           break;
145
         default:
145
         default:
146
-          new_fan_speed[fan] = MIN(tmp_temp, 255U);
146
+          new_fan_speed[fan] = _MIN(tmp_temp, 255U);
147
           break;
147
           break;
148
       }
148
       }
149
     }
149
     }
163
 
163
 
164
     uint8_t Temperature::lcd_tmpfan_speed[
164
     uint8_t Temperature::lcd_tmpfan_speed[
165
       #if ENABLED(SINGLENOZZLE)
165
       #if ENABLED(SINGLENOZZLE)
166
-        MAX(EXTRUDERS, FAN_COUNT)
166
+        _MAX(EXTRUDERS, FAN_COUNT)
167
       #else
167
       #else
168
         FAN_COUNT
168
         FAN_COUNT
169
       #endif
169
       #endif
976
   updateTemperaturesFromRawValues(); // also resets the watchdog
976
   updateTemperaturesFromRawValues(); // also resets the watchdog
977
 
977
 
978
   #if ENABLED(HEATER_0_USES_MAX6675)
978
   #if ENABLED(HEATER_0_USES_MAX6675)
979
-    if (temp_hotend[0].current > MIN(HEATER_0_MAXTEMP, HEATER_0_MAX6675_TMAX - 1.0)) max_temp_error(H_E0);
980
-    if (temp_hotend[0].current < MAX(HEATER_0_MINTEMP, HEATER_0_MAX6675_TMIN + .01)) min_temp_error(H_E0);
979
+    if (temp_hotend[0].current > _MIN(HEATER_0_MAXTEMP, HEATER_0_MAX6675_TMAX - 1.0)) max_temp_error(H_E0);
980
+    if (temp_hotend[0].current < _MAX(HEATER_0_MINTEMP, HEATER_0_MAX6675_TMIN + .01)) min_temp_error(H_E0);
981
   #endif
981
   #endif
982
 
982
 
983
   #if ENABLED(HEATER_1_USES_MAX6675)
983
   #if ENABLED(HEATER_1_USES_MAX6675)
984
-    if (temp_hotend[1].current > MIN(HEATER_1_MAXTEMP, HEATER_1_MAX6675_TMAX - 1.0)) max_temp_error(H_E1);
985
-    if (temp_hotend[1].current < MAX(HEATER_1_MINTEMP, HEATER_1_MAX6675_TMIN + .01)) min_temp_error(H_E1);
984
+    if (temp_hotend[1].current > _MIN(HEATER_1_MAXTEMP, HEATER_1_MAX6675_TMAX - 1.0)) max_temp_error(H_E1);
985
+    if (temp_hotend[1].current < _MAX(HEATER_1_MINTEMP, HEATER_1_MAX6675_TMIN + .01)) min_temp_error(H_E1);
986
   #endif
986
   #endif
987
 
987
 
988
   #define HAS_THERMAL_PROTECTION (ENABLED(THERMAL_PROTECTION_HOTENDS) || HAS_THERMALLY_PROTECTED_BED || ENABLED(THERMAL_PROTECTION_CHAMBER))
988
   #define HAS_THERMAL_PROTECTION (ENABLED(THERMAL_PROTECTION_HOTENDS) || HAS_THERMALLY_PROTECTED_BED || ENABLED(THERMAL_PROTECTION_CHAMBER))
1325
     //#endif
1325
     //#endif
1326
 
1326
 
1327
     // Return degrees C (up to 999, as the LCD only displays 3 digits)
1327
     // Return degrees C (up to 999, as the LCD only displays 3 digits)
1328
-    return MIN(value + THERMISTOR_ABS_ZERO_C, 999);
1328
+    return _MIN(value + THERMISTOR_ABS_ZERO_C, 999);
1329
   }
1329
   }
1330
 #endif
1330
 #endif
1331
 
1331
 
1884
 
1884
 
1885
         #if ENABLED(ADAPTIVE_FAN_SLOWING)
1885
         #if ENABLED(ADAPTIVE_FAN_SLOWING)
1886
           if (adaptive_fan_slowing && heater_id >= 0) {
1886
           if (adaptive_fan_slowing && heater_id >= 0) {
1887
-            const int fan_index = MIN(heater_id, FAN_COUNT - 1);
1887
+            const int fan_index = _MIN(heater_id, FAN_COUNT - 1);
1888
             if (fan_speed[fan_index] == 0 || current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.25f))
1888
             if (fan_speed[fan_index] == 0 || current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.25f))
1889
               fan_speed_scaler[fan_index] = 128;
1889
               fan_speed_scaler[fan_index] = 128;
1890
             else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.3335f))
1890
             else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.3335f))

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

140
 // get all oversampled sensor readings
140
 // get all oversampled sensor readings
141
 #define MIN_ADC_ISR_LOOPS 10
141
 #define MIN_ADC_ISR_LOOPS 10
142
 
142
 
143
-#define ACTUAL_ADC_SAMPLES MAX(int(MIN_ADC_ISR_LOOPS), int(SensorsReady))
143
+#define ACTUAL_ADC_SAMPLES _MAX(int(MIN_ADC_ISR_LOOPS), int(SensorsReady))
144
 
144
 
145
 #if HAS_PID_HEATING
145
 #if HAS_PID_HEATING
146
   #define PID_K2 (1-float(PID_K1))
146
   #define PID_K2 (1-float(PID_K1))
496
 
496
 
497
         static uint8_t lcd_tmpfan_speed[
497
         static uint8_t lcd_tmpfan_speed[
498
           #if ENABLED(SINGLENOZZLE)
498
           #if ENABLED(SINGLENOZZLE)
499
-            MAX(EXTRUDERS, FAN_COUNT)
499
+            _MAX(EXTRUDERS, FAN_COUNT)
500
           #else
500
           #else
501
             FAN_COUNT
501
             FAN_COUNT
502
           #endif
502
           #endif
613
       #if ENABLED(AUTO_POWER_CONTROL)
613
       #if ENABLED(AUTO_POWER_CONTROL)
614
         powerManager.power_on();
614
         powerManager.power_on();
615
       #endif
615
       #endif
616
-      temp_hotend[ee].target = MIN(celsius, temp_range[ee].maxtemp - 15);
616
+      temp_hotend[ee].target = _MIN(celsius, temp_range[ee].maxtemp - 15);
617
       start_watching_hotend(ee);
617
       start_watching_hotend(ee);
618
     }
618
     }
619
 
619
 
627
       static void setTargetChamber(const int16_t celsius) {
627
       static void setTargetChamber(const int16_t celsius) {
628
         temp_chamber.target =
628
         temp_chamber.target =
629
           #ifdef CHAMBER_MAXTEMP
629
           #ifdef CHAMBER_MAXTEMP
630
-            MIN(celsius, CHAMBER_MAXTEMP)
630
+            _MIN(celsius, CHAMBER_MAXTEMP)
631
           #else
631
           #else
632
             celsius
632
             celsius
633
           #endif
633
           #endif
676
         #endif
676
         #endif
677
         temp_bed.target =
677
         temp_bed.target =
678
           #ifdef BED_MAXTEMP
678
           #ifdef BED_MAXTEMP
679
-            MIN(celsius, BED_MAXTEMP - 10)
679
+            _MIN(celsius, BED_MAXTEMP - 10)
680
           #else
680
           #else
681
             celsius
681
             celsius
682
           #endif
682
           #endif

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

942
       #elif ENABLED(SWITCHING_NOZZLE) && !SWITCHING_NOZZLE_TWO_SERVOS   // Switching Nozzle (single servo)
942
       #elif ENABLED(SWITCHING_NOZZLE) && !SWITCHING_NOZZLE_TWO_SERVOS   // Switching Nozzle (single servo)
943
         // Raise by a configured distance to avoid workpiece, except with
943
         // Raise by a configured distance to avoid workpiece, except with
944
         // SWITCHING_NOZZLE_TWO_SERVOS, as both nozzles will lift instead.
944
         // SWITCHING_NOZZLE_TWO_SERVOS, as both nozzles will lift instead.
945
-        current_position[Z_AXIS] += MAX(-zdiff, 0.0) + toolchange_settings.z_raise;
945
+        current_position[Z_AXIS] += _MAX(-zdiff, 0.0) + toolchange_settings.z_raise;
946
         #if HAS_SOFTWARE_ENDSTOPS
946
         #if HAS_SOFTWARE_ENDSTOPS
947
           NOMORE(current_position[Z_AXIS], soft_endstop[Z_AXIS].max);
947
           NOMORE(current_position[Z_AXIS], soft_endstop[Z_AXIS].max);
948
         #endif
948
         #endif

Loading…
Cancel
Save