Browse Source

Replace MIN# / MAX# with variadic MIN / MAX (#11960)

pull/1/head
AnoNymous 6 years ago
committed by Scott Lahteine
parent
commit
b30ca652ae
  1. 51
      Marlin/src/core/macros.h
  2. 68
      Marlin/src/core/minmax.h
  3. 4
      Marlin/src/feature/leds/tempstat.cpp
  4. 2
      Marlin/src/gcode/calibrate/G33.cpp
  5. 2
      Marlin/src/inc/Conditionals_post.h
  6. 16
      Marlin/src/lcd/ultralcd.cpp
  7. 2
      Marlin/src/module/motion.cpp
  8. 8
      Marlin/src/module/planner.cpp
  9. 7
      frameworks/CMSIS/LPC1768/include/lpc_types.h

51
Marlin/src/core/macros.h

@ -20,8 +20,9 @@
* *
*/ */
#ifndef _CORE_MACROS_H_ #pragma once
#define _CORE_MACROS_H_
#include "minmax.h"
#define NUM_AXIS 4 #define NUM_AXIS 4
#define ABCE 4 #define ABCE 4
@ -93,10 +94,6 @@
#define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1))) #define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1)))
// Macros to constrain values // Macros to constrain values
// Avoid double evaluation of arguments to NOMORE/NOLESS/LIMIT
#undef NOMORE
#undef NOLESS
#undef LIMIT
#ifdef __cplusplus #ifdef __cplusplus
// C++11 solution that is standards compliant. // C++11 solution that is standards compliant.
@ -207,49 +204,13 @@
#define CEILING(x,y) (((x) + (y) - 1) / (y)) #define CEILING(x,y) (((x) + (y) - 1) / (y))
// Avoid double evaluation of arguments on MIN/MAX/ABS
#undef MIN
#undef MAX
#undef ABS #undef ABS
#ifdef __cplusplus #ifdef __cplusplus
template <class T> static inline constexpr const T ABS(const T v) { return v >= 0 ? v : -v; }
// C++11 solution that is standards compliant. Return type is deduced automatically
template <class L, class R> static inline constexpr auto MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) {
return lhs < rhs ? lhs : rhs;
}
template <class L, class R> static inline constexpr auto MAX(const L lhs, const R rhs) -> decltype(lhs + rhs){
return lhs > rhs ? lhs : rhs;
}
template <class T> static inline constexpr const T ABS(const T v) {
return v >= 0 ? v : -v;
}
#else #else
#define ABS(a) ({__typeof__(a) _a = (a); _a >= 0 ? _a : -_a;})
// Using GCC extensions, but Travis GCC version does not like it and gives
// "error: statement-expressions are not allowed outside functions nor in template-argument lists"
#define MIN(a, b) \
({__typeof__(a) _a = (a); \
__typeof__(b) _b = (b); \
_a < _b ? _a : _b;})
#define MAX(a, b) \
({__typeof__(a) _a = (a); \
__typeof__(b) _b = (b); \
_a > _b ? _a : _b;})
#define ABS(a) \
({__typeof__(a) _a = (a); \
_a >= 0 ? _a : -_a;})
#endif #endif
#define MIN3(a, b, c) MIN(MIN(a, b), c)
#define MIN4(a, b, c, d) MIN(MIN3(a, b, c), d)
#define MIN5(a, b, c, d, e) MIN(MIN4(a, b, c, d), e)
#define MAX3(a, b, c) MAX(MAX(a, b), c)
#define MAX4(a, b, c, d) MAX(MAX3(a, b, c), d)
#define MAX5(a, b, c, d, e) MAX(MAX4(a, b, c, d), e)
#define UNEAR_ZERO(x) ((x) < 0.000001f) #define UNEAR_ZERO(x) ((x) < 0.000001f)
#define NEAR_ZERO(x) WITHIN(x, -0.000001f, 0.000001f) #define NEAR_ZERO(x) WITHIN(x, -0.000001f, 0.000001f)
#define NEAR(x,y) NEAR_ZERO((x)-(y)) #define NEAR(x,y) NEAR_ZERO((x)-(y))
@ -269,5 +230,3 @@
#define LROUND(x) lroundf(x) #define LROUND(x) lroundf(x)
#define FMOD(x, y) fmodf(x, y) #define FMOD(x, y) fmodf(x, y)
#define HYPOT(x,y) SQRT(HYPOT2(x,y)) #define HYPOT(x,y) SQRT(HYPOT2(x,y))
#endif // _CORE_MACROS_H_

68
Marlin/src/core/minmax.h

@ -0,0 +1,68 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#undef MIN
#undef MAX
#ifdef __cplusplus
extern "C++" {
// C++11 solution that is standards compliant. Return type is deduced automatically
template <class L, class R> static inline constexpr auto MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) {
return lhs < rhs ? lhs : rhs;
}
template <class L, class R> static inline constexpr auto MAX(const L lhs, const R rhs) -> decltype(lhs + rhs) {
return lhs > rhs ? lhs : rhs;
}
template<class T, class ... Ts> static inline constexpr const T MIN(T V, Ts... Vs) { return MIN(V, MIN(Vs...)); }
template<class T, class ... Ts> static inline constexpr const T MAX(T V, Ts... Vs) { return MAX(V, MAX(Vs...)); }
}
#else
// NUM_ARGS(...) evaluates to the number of arguments
#define _NUM_ARGS(X,X6,X5,X4,X3,X2,X1,N,...) N
#define NUM_ARGS(...) _NUM_ARGS(0, __VA_ARGS__ ,6,5,4,3,2,1,0)
#define MIN_2(a,b) ({__typeof__(a) _a = (a); __typeof__(b) _b = (b); _a > _b ? _a : _b;})
#define MIN_3(a,...) MIN_2(a,MIN_2(__VA_ARGS__))
#define MIN_4(a,...) MIN_2(a,MIN_3(__VA_ARGS__))
#define MIN_5(a,...) MIN_2(a,MIN_4(__VA_ARGS__))
#define MIN_6(a,...) MIN_2(a,MIN_4(__VA_ARGS__))
#define __MIN_N(N, ...) MIN_ ## N(__VA_ARGS__)
#define _MIN_N(N, ...) __MIN_N(N, __VA_ARGS__)
#define MIN(...) _MIN_N(NUM_ARGS(__VA_ARGS__), __VA_ARGS__)
#define MAX_2(a,b) ({__typeof__(a) _a = (a); __typeof__(b) _b = (b); _a > _b ? _a : _b;})
#define MAX_3(a,...) MAX_2(a,MAX_2(__VA_ARGS__))
#define MAX_4(a,...) MAX_2(a,MAX_3(__VA_ARGS__))
#define MAX_5(a,...) MAX_2(a,MAX_4(__VA_ARGS__))
#define MAX_6(a,...) MAX_2(a,MAX_4(__VA_ARGS__))
#define __MAX_N(N, ...) MAX_ ## N(__VA_ARGS__)
#define _MAX_N(N, ...) __MAX_N(N, __VA_ARGS__)
#define MAX(...) _MAX_N(NUM_ARGS(__VA_ARGS__), __VA_ARGS__)
#endif

4
Marlin/src/feature/leds/tempstat.cpp

@ -38,10 +38,10 @@ void handle_status_leds(void) {
next_status_led_update_ms += 500; // Update every 0.5s next_status_led_update_ms += 500; // Update every 0.5s
float max_temp = 0.0; float max_temp = 0.0;
#if HAS_HEATED_BED #if HAS_HEATED_BED
max_temp = MAX3(max_temp, thermalManager.degTargetBed(), thermalManager.degBed()); max_temp = MAX(max_temp, thermalManager.degTargetBed(), thermalManager.degBed());
#endif #endif
HOTEND_LOOP() HOTEND_LOOP()
max_temp = MAX3(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e)); max_temp = MAX(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e));
const bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led; const bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led;
if (new_led != red_led) { if (new_led != red_led) {
red_led = new_led; red_led = new_led;

2
Marlin/src/gcode/calibrate/G33.cpp

@ -651,7 +651,7 @@ void GcodeSuite::G33() {
} }
// adjust delta_height and endstops by the max amount // adjust delta_height and endstops by the max amount
const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]); const float z_temp = MAX(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
delta_height -= z_temp; delta_height -= z_temp;
LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp; LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp;
} }

2
Marlin/src/inc/Conditionals_post.h

@ -1255,7 +1255,7 @@
#define _PROBE_RADIUS (DELTA_PRINTABLE_RADIUS - (MIN_PROBE_EDGE)) #define _PROBE_RADIUS (DELTA_PRINTABLE_RADIUS - (MIN_PROBE_EDGE))
#ifndef DELTA_CALIBRATION_RADIUS #ifndef DELTA_CALIBRATION_RADIUS
#ifdef X_PROBE_OFFSET_FROM_EXTRUDER #ifdef X_PROBE_OFFSET_FROM_EXTRUDER
#define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - MAX3(abs(X_PROBE_OFFSET_FROM_EXTRUDER), abs(Y_PROBE_OFFSET_FROM_EXTRUDER), abs(MIN_PROBE_EDGE))) #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - MAX(ABS(X_PROBE_OFFSET_FROM_EXTRUDER), ABS(Y_PROBE_OFFSET_FROM_EXTRUDER), ABS(MIN_PROBE_EDGE)))
#else #else
#define DELTA_CALIBRATION_RADIUS _PROBE_RADIUS #define DELTA_CALIBRATION_RADIUS _PROBE_RADIUS
#endif #endif

16
Marlin/src/lcd/ultralcd.cpp

@ -3697,17 +3697,17 @@ void lcd_quick_feedback(const bool clear_buttons) {
void _lcd_configuration_temperature_preheat_settings_menu(const uint8_t material) { void _lcd_configuration_temperature_preheat_settings_menu(const uint8_t material) {
#if HOTENDS > 5 #if HOTENDS > 5
#define MINTEMP_ALL MIN5(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP, HEATER_5_MINTEMP) #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP, HEATER_5_MINTEMP)
#define MAXTEMP_ALL MAX5(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP) #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP)
#elif HOTENDS > 4 #elif HOTENDS > 4
#define MINTEMP_ALL MIN5(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP) #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP, HEATER_4_MINTEMP)
#define MAXTEMP_ALL MAX5(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP) #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP)
#elif HOTENDS > 3 #elif HOTENDS > 3
#define MINTEMP_ALL MIN4(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP) #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP)
#define MAXTEMP_ALL MAX4(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP) #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP)
#elif HOTENDS > 2 #elif HOTENDS > 2
#define MINTEMP_ALL MIN3(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP) #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP)
#define MAXTEMP_ALL MAX3(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP) #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP)
#elif HOTENDS > 1 #elif HOTENDS > 1
#define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP) #define MINTEMP_ALL MIN(HEATER_0_MINTEMP, HEATER_1_MINTEMP)
#define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP) #define MAXTEMP_ALL MAX(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP)

2
Marlin/src/module/motion.cpp

@ -1541,7 +1541,7 @@ void homeaxis(const AxisEnum axis) {
case X_AXIS: case X_AXIS:
case Y_AXIS: case Y_AXIS:
// Get a minimum radius for clamping // Get a minimum radius for clamping
soft_endstop_radius = MIN3(ABS(MAX(soft_endstop_min[X_AXIS], soft_endstop_min[Y_AXIS])), soft_endstop_max[X_AXIS], soft_endstop_max[Y_AXIS]); soft_endstop_radius = MIN(ABS(MAX(soft_endstop_min[X_AXIS], soft_endstop_min[Y_AXIS])), soft_endstop_max[X_AXIS], soft_endstop_max[Y_AXIS]);
soft_endstop_radius_2 = sq(soft_endstop_radius); soft_endstop_radius_2 = sq(soft_endstop_radius);
break; break;
#endif #endif

8
Marlin/src/module/planner.cpp

@ -1762,7 +1762,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
#endif #endif
block->steps[E_AXIS] = esteps; block->steps[E_AXIS] = esteps;
block->step_event_count = MAX4(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], esteps); block->step_event_count = MAX(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], esteps);
// Bail if this is a zero-length block // Bail if this is a zero-length block
if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false; if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false;
@ -2120,8 +2120,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
} }
ys0 = axis_segment_time_us[Y_AXIS][0] = ys0 + segment_time_us; ys0 = axis_segment_time_us[Y_AXIS][0] = ys0 + segment_time_us;
const uint32_t max_x_segment_time = MAX3(xs0, xs1, xs2), const uint32_t max_x_segment_time = MAX(xs0, xs1, xs2),
max_y_segment_time = MAX3(ys0, ys1, ys2), max_y_segment_time = MAX(ys0, ys1, ys2),
min_xy_segment_time = MIN(max_x_segment_time, max_y_segment_time); min_xy_segment_time = MIN(max_x_segment_time, max_y_segment_time);
if (min_xy_segment_time < MAX_FREQ_TIME_US) { if (min_xy_segment_time < MAX_FREQ_TIME_US) {
const float low_sf = speed_factor * min_xy_segment_time / (MAX_FREQ_TIME_US); const float low_sf = speed_factor * min_xy_segment_time / (MAX_FREQ_TIME_US);
@ -2354,7 +2354,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
} }
// Get the lowest speed // Get the lowest speed
vmax_junction_sqr = MIN3(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr); vmax_junction_sqr = MIN(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr);
} }
else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later. else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later.
vmax_junction_sqr = 0; vmax_junction_sqr = 0;

7
frameworks/CMSIS/LPC1768/include/lpc_types.h

@ -145,12 +145,7 @@ typedef int32_t(*PFI)();
/* External data/function define */ /* External data/function define */
#define EXTERN extern #define EXTERN extern
#ifndef MAX #include "../../../../src/core/minmax.h"
#define MAX(a, b) (((a) > (b)) ? (a) : (b))
#endif
#ifndef MIN
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
#endif
/** /**
* @} * @}

Loading…
Cancel
Save