Smarter MIN, MAX, ABS macros

Use macros that explicitly avoid double-evaluation and can be used for any datatype, replacing `min`, `max`, `abs`, `fabs`, `labs`, and `FABS`.

Co-Authored-By: ejtagle <ejtagle@hotmail.com>
This commit is contained in:
Scott Lahteine
2018-05-13 01:10:34 -05:00
parent 083ec9963e
commit 99ecdf59af
52 changed files with 206 additions and 247 deletions

View File

@ -150,7 +150,7 @@ float delta_safe_distance_from_top() {
float centered_extent = delta[A_AXIS];
cartesian[Y_AXIS] = DELTA_PRINTABLE_RADIUS;
inverse_kinematics(cartesian);
return FABS(centered_extent - delta[A_AXIS]);
return ABS(centered_extent - delta[A_AXIS]);
}
/**

View File

@ -552,7 +552,7 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
float cartesian_mm = SQRT(sq(xdiff) + sq(ydiff) + sq(zdiff));
// If the move is very short, check the E move distance
if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = FABS(ediff);
if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(ediff);
// No E move either? Game over.
if (UNEAR_ZERO(cartesian_mm)) return true;
@ -665,6 +665,7 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
const float diff2 = HYPOT2(delta[A_AXIS] - oldA, delta[B_AXIS] - oldB);
if (diff2) {
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], rtarget[Z_AXIS], rtarget[E_AXIS], SQRT(diff2) * inverse_secs, active_extruder);
/*
SERIAL_ECHOPAIR("final: A=", delta[A_AXIS]); SERIAL_ECHOPAIR(" B=", delta[B_AXIS]);
SERIAL_ECHOPAIR(" adiff=", delta[A_AXIS] - oldA); SERIAL_ECHOPAIR(" bdiff=", delta[B_AXIS] - oldB);
@ -710,7 +711,7 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
// If the move is very short, check the E move distance
// No E move either? Game over.
float cartesian_mm = SQRT(sq(xdiff) + sq(ydiff) + sq(zdiff));
if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = FABS(ediff);
if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(ediff);
if (UNEAR_ZERO(cartesian_mm)) return;
// The length divided by the segment size
@ -921,7 +922,7 @@ void prepare_move_to_destination() {
}
#endif // PREVENT_COLD_EXTRUSION
#if ENABLED(PREVENT_LENGTHY_EXTRUDE)
if (FABS(destination[E_AXIS] - current_position[E_AXIS]) * planner.e_factor[active_extruder] > (EXTRUDE_MAXLENGTH)) {
if (ABS(destination[E_AXIS] - current_position[E_AXIS]) * planner.e_factor[active_extruder] > (EXTRUDE_MAXLENGTH)) {
current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part
SERIAL_ECHO_START();
SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
@ -1289,7 +1290,7 @@ void homeaxis(const AxisEnum axis) {
// When homing Z with probe respect probe clearance
const float bump = axis_home_dir * (
#if HOMING_Z_WITH_PROBE
(axis == Z_AXIS && (Z_HOME_BUMP_MM)) ? max(Z_CLEARANCE_BETWEEN_PROBES, Z_HOME_BUMP_MM) :
(axis == Z_AXIS && (Z_HOME_BUMP_MM)) ? MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_HOME_BUMP_MM) :
#endif
home_bump_mm(axis)
);
@ -1318,7 +1319,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(X_DUAL_ENDSTOPS)
if (axis == X_AXIS) {
const bool lock_x1 = pos_dir ? (endstops.x_endstop_adj > 0) : (endstops.x_endstop_adj < 0);
float adj = FABS(endstops.x_endstop_adj);
float adj = ABS(endstops.x_endstop_adj);
if (pos_dir) adj = -adj;
if (lock_x1) stepper.set_x_lock(true); else stepper.set_x2_lock(true);
do_homing_move(axis, adj);
@ -1329,7 +1330,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(Y_DUAL_ENDSTOPS)
if (axis == Y_AXIS) {
const bool lock_y1 = pos_dir ? (endstops.y_endstop_adj > 0) : (endstops.y_endstop_adj < 0);
float adj = FABS(endstops.y_endstop_adj);
float adj = ABS(endstops.y_endstop_adj);
if (pos_dir) adj = -adj;
if (lock_y1) stepper.set_y_lock(true); else stepper.set_y2_lock(true);
do_homing_move(axis, adj);
@ -1340,7 +1341,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(Z_DUAL_ENDSTOPS)
if (axis == Z_AXIS) {
const bool lock_z1 = pos_dir ? (endstops.z_endstop_adj > 0) : (endstops.z_endstop_adj < 0);
float adj = FABS(endstops.z_endstop_adj);
float adj = ABS(endstops.z_endstop_adj);
if (pos_dir) adj = -adj;
if (lock_z1) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
do_homing_move(axis, adj);
@ -1424,7 +1425,7 @@ void homeaxis(const AxisEnum axis) {
if (axis == X_AXIS) {
// In Dual X mode hotend_offset[X] is T1's home position
float dual_max_x = max(hotend_offset[X_AXIS][1], X2_MAX_POS);
float dual_max_x = MAX(hotend_offset[X_AXIS][1], X2_MAX_POS);
if (active_extruder != 0) {
// T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger)
@ -1435,7 +1436,7 @@ void homeaxis(const AxisEnum axis) {
// In Duplication Mode, T0 can move as far left as X_MIN_POS
// but not so far to the right that T1 would move past the end
soft_endstop_min[X_AXIS] = base_min_pos(X_AXIS);
soft_endstop_max[X_AXIS] = min(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset);
soft_endstop_max[X_AXIS] = MIN(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset);
}
else {
// In other modes, T0 can move from X_MIN_POS to X_MAX_POS
@ -1471,7 +1472,7 @@ void homeaxis(const AxisEnum axis) {
case X_AXIS:
case Y_AXIS:
// Get a minimum radius for clamping
soft_endstop_radius = MIN3(FABS(max(soft_endstop_min[X_AXIS], soft_endstop_min[Y_AXIS])), soft_endstop_max[X_AXIS], soft_endstop_max[Y_AXIS]);
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_2 = sq(soft_endstop_radius);
break;
#endif

View File

@ -260,7 +260,7 @@ void homeaxis(const AxisEnum axis);
// Note: This won't work on SCARA since the probe offset rotates with the arm.
inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
return position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER))
&& position_is_reachable(rx, ry, FABS(MIN_PROBE_EDGE));
&& position_is_reachable(rx, ry, ABS(MIN_PROBE_EDGE));
}
#endif

View File

@ -833,7 +833,7 @@ void Planner::reverse_pass_kernel(block_t* const current, const block_t* const n
// for max allowable speed if block is decelerating and nominal length is false.
const float new_entry_speed = (TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH) || max_entry_speed <= next->entry_speed)
? max_entry_speed
: min(max_entry_speed, max_allowable_speed(-current->acceleration, next->entry_speed, current->millimeters));
: MIN(max_entry_speed, max_allowable_speed(-current->acceleration, next->entry_speed, current->millimeters));
if (new_entry_speed != current->entry_speed) {
current->entry_speed = new_entry_speed;
SBI(current->flag, BLOCK_BIT_RECALCULATE);
@ -859,7 +859,7 @@ void Planner::reverse_pass() {
// for max allowable speed if block is decelerating and nominal length is false.
const float new_entry_speed = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
? max_entry_speed
: min(max_entry_speed, max_allowable_speed(-current->acceleration, MINIMUM_PLANNER_SPEED, current->millimeters));
: MIN(max_entry_speed, max_allowable_speed(-current->acceleration, MINIMUM_PLANNER_SPEED, current->millimeters));
if (current->entry_speed != new_entry_speed) {
current->entry_speed = new_entry_speed;
SBI(current->flag, BLOCK_BIT_RECALCULATE);
@ -884,7 +884,7 @@ void Planner::forward_pass_kernel(const block_t* const previous, block_t* const
// guaranteed to be reached. No need to recheck.
if (!TEST(previous->flag, BLOCK_BIT_NOMINAL_LENGTH)) {
if (previous->entry_speed < current->entry_speed) {
const float new_entry_speed = min(current->entry_speed, max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters));
const float new_entry_speed = MIN(current->entry_speed, max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters));
// Check for junction speed change
if (current->entry_speed != new_entry_speed) {
current->entry_speed = new_entry_speed;
@ -1384,7 +1384,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
}
#endif // PREVENT_COLD_EXTRUSION
#if ENABLED(PREVENT_LENGTHY_EXTRUDE)
if (labs(de * e_factor[extruder]) > (int32_t)axis_steps_per_mm[E_AXIS_N] * (EXTRUDE_MAXLENGTH)) { // It's not important to get max. extrusion length in a precision < 1mm, so save some cycles and cast to int
if (ABS(de * e_factor[extruder]) > (int32_t)axis_steps_per_mm[E_AXIS_N] * (EXTRUDE_MAXLENGTH)) { // It's not important to get max. extrusion length in a precision < 1mm, so save some cycles and cast to int
position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part
#if HAS_POSITION_FLOAT
position_float[E_AXIS] = target_float[E_AXIS];
@ -1425,7 +1425,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
if (de < 0) SBI(dm, E_AXIS);
const float esteps_float = de * e_factor[extruder];
const int32_t esteps = abs(esteps_float) + 0.5;
const int32_t esteps = ABS(esteps_float) + 0.5;
// Wait for the next available block
uint8_t next_buffer_head;
@ -1440,26 +1440,26 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
// Number of steps for each axis
// See http://www.corexy.com/theory.html
#if CORE_IS_XY
block->steps[A_AXIS] = labs(da + db);
block->steps[B_AXIS] = labs(da - db);
block->steps[Z_AXIS] = labs(dc);
block->steps[A_AXIS] = ABS(da + db);
block->steps[B_AXIS] = ABS(da - db);
block->steps[Z_AXIS] = ABS(dc);
#elif CORE_IS_XZ
block->steps[A_AXIS] = labs(da + dc);
block->steps[Y_AXIS] = labs(db);
block->steps[C_AXIS] = labs(da - dc);
block->steps[A_AXIS] = ABS(da + dc);
block->steps[Y_AXIS] = ABS(db);
block->steps[C_AXIS] = ABS(da - dc);
#elif CORE_IS_YZ
block->steps[X_AXIS] = labs(da);
block->steps[B_AXIS] = labs(db + dc);
block->steps[C_AXIS] = labs(db - dc);
block->steps[X_AXIS] = ABS(da);
block->steps[B_AXIS] = ABS(db + dc);
block->steps[C_AXIS] = ABS(db - dc);
#elif IS_SCARA
block->steps[A_AXIS] = labs(da);
block->steps[B_AXIS] = labs(db);
block->steps[Z_AXIS] = labs(dc);
block->steps[A_AXIS] = ABS(da);
block->steps[B_AXIS] = ABS(db);
block->steps[Z_AXIS] = ABS(dc);
#else
// default non-h-bot planning
block->steps[A_AXIS] = labs(da);
block->steps[B_AXIS] = labs(db);
block->steps[C_AXIS] = labs(dc);
block->steps[A_AXIS] = ABS(da);
block->steps[B_AXIS] = ABS(db);
block->steps[C_AXIS] = ABS(dc);
#endif
block->steps[E_AXIS] = esteps;
@ -1660,7 +1660,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
delta_mm[E_AXIS] = esteps_float * steps_to_mm[E_AXIS_N];
if (block->steps[A_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[B_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[C_AXIS] < MIN_STEPS_PER_SEGMENT) {
block->millimeters = FABS(delta_mm[E_AXIS]);
block->millimeters = ABS(delta_mm[E_AXIS]);
}
else if (!millimeters) {
block->millimeters = SQRT(
@ -1751,7 +1751,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
// Calculate and limit speed in mm/sec for each axis
float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed
LOOP_XYZE(i) {
const float cs = FABS((current_speed[i] = delta_mm[i] * inverse_secs));
const float cs = ABS((current_speed[i] = delta_mm[i] * inverse_secs));
#if ENABLED(DISTINCT_E_FACTORS)
if (i == E_AXIS) i += extruder;
#endif
@ -1789,7 +1789,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
const uint32_t max_x_segment_time = MAX3(xs0, xs1, xs2),
max_y_segment_time = MAX3(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) {
const float low_sf = speed_factor * min_xy_segment_time / (MAX_FREQ_TIME_US);
NOMORE(speed_factor, low_sf);
@ -1973,7 +1973,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
vmax_junction = MINIMUM_PLANNER_SPEED;
}
else {
junction_cos_theta = max(junction_cos_theta, -0.999999); // Check for numerical round-off to avoid divide by zero.
junction_cos_theta = MAX(junction_cos_theta, -0.999999); // Check for numerical round-off to avoid divide by zero.
const float sin_theta_d2 = SQRT(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive.
// TODO: Technically, the acceleration used in calculation needs to be limited by the minimum of the
@ -2003,7 +2003,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
float safe_speed = block->nominal_speed;
uint8_t limited = 0;
LOOP_XYZE(i) {
const float jerk = FABS(current_speed[i]), maxj = max_jerk[i];
const float jerk = ABS(current_speed[i]), maxj = max_jerk[i];
if (jerk > maxj) {
if (limited) {
const float mjerk = maxj * block->nominal_speed;
@ -2023,7 +2023,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
// The junction velocity will be shared between successive segments. Limit the junction velocity to their minimum.
// Pick the smaller of the nominal speeds. Higher speed shall not be achieved at the junction during coasting.
vmax_junction = min(block->nominal_speed, previous_nominal_speed);
vmax_junction = MIN(block->nominal_speed, previous_nominal_speed);
// Factor to multiply the previous / current nominal velocities to get componentwise limited velocities.
float v_factor = 1;
@ -2043,9 +2043,9 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
// Calculate jerk depending on whether the axis is coasting in the same direction or reversing.
const float jerk = (v_exit > v_entry)
? // coasting axis reversal
( (v_entry > 0 || v_exit < 0) ? (v_exit - v_entry) : max(v_exit, -v_entry) )
( (v_entry > 0 || v_exit < 0) ? (v_exit - v_entry) : MAX(v_exit, -v_entry) )
: // v_exit <= v_entry coasting axis reversal
( (v_entry < 0 || v_exit > 0) ? (v_entry - v_exit) : max(-v_exit, v_entry) );
( (v_entry < 0 || v_exit > 0) ? (v_entry - v_exit) : MAX(-v_exit, v_entry) );
if (jerk > max_jerk[axis]) {
v_factor *= max_jerk[axis] / jerk;
@ -2072,7 +2072,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
const float v_allowable = max_allowable_speed(-block->acceleration, MINIMUM_PLANNER_SPEED, block->millimeters);
// If stepper ISR is disabled, this indicates buffer_segment wants to add a split block.
// In this case start with the max. allowed speed to avoid an interrupted first move.
block->entry_speed = STEPPER_ISR_ENABLED() ? MINIMUM_PLANNER_SPEED : min(vmax_junction, v_allowable);
block->entry_speed = STEPPER_ISR_ENABLED() ? MINIMUM_PLANNER_SPEED : MIN(vmax_junction, v_allowable);
// Initialize planner efficiency flags
// Set flag if block will always reach maximum junction speed regardless of entry/exit speeds.

View File

@ -710,7 +710,7 @@ class Planner {
};
#define PLANNER_XY_FEEDRATE() (min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]))
#define PLANNER_XY_FEEDRATE() (MIN(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]))
extern Planner planner;

View File

@ -67,7 +67,7 @@ inline static float eval_bezier(float a, float b, float c, float d, float t) {
* We approximate Euclidean distance with the sum of the coordinates
* offset (so-called "norm 1"), which is quicker to compute.
*/
inline static float dist1(float x1, float y1, float x2, float y2) { return FABS(x1 - x2) + FABS(y1 - y2); }
inline static float dist1(float x1, float y1, float x2, float y2) { return ABS(x1 - x2) + ABS(y1 - y2); }
/**
* The algorithm for computing the step is loosely based on the one in Kig

View File

@ -392,7 +392,7 @@ bool set_probe_deployed(const bool deploy) {
#endif
if (deploy_stow_condition && unknown_condition)
do_probe_raise(max(Z_CLEARANCE_BETWEEN_PROBES, Z_CLEARANCE_DEPLOY_PROBE));
do_probe_raise(MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_CLEARANCE_DEPLOY_PROBE));
#if ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY)
#if ENABLED(Z_PROBE_SLED)
@ -672,7 +672,7 @@ float probe_pt(const float &rx, const float &ry, const ProbePtRaise raise_after/
const float nz =
#if ENABLED(DELTA)
// Move below clip height or xy move will be aborted by do_blocking_move_to
min(current_position[Z_AXIS], delta_clip_start_height)
MIN(current_position[Z_AXIS], delta_clip_start_height)
#else
current_position[Z_AXIS]
#endif

View File

@ -811,8 +811,8 @@ void Temperature::manage_heater() {
updateTemperaturesFromRawValues(); // also resets the watchdog
#if ENABLED(HEATER_0_USES_MAX6675)
if (current_temperature[0] > min(HEATER_0_MAXTEMP, MAX6675_TMAX - 1.0)) max_temp_error(0);
if (current_temperature[0] < max(HEATER_0_MINTEMP, MAX6675_TMIN + .01)) min_temp_error(0);
if (current_temperature[0] > MIN(HEATER_0_MAXTEMP, MAX6675_TMAX - 1.0)) max_temp_error(0);
if (current_temperature[0] < MAX(HEATER_0_MINTEMP, MAX6675_TMIN + .01)) min_temp_error(0);
#endif
#if WATCH_HOTENDS || WATCH_THE_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN || HEATER_IDLE_HANDLER
@ -845,7 +845,7 @@ void Temperature::manage_heater() {
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
// Make sure measured temperatures are close together
if (FABS(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF)
if (ABS(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF)
_temp_error(0, PSTR(MSG_REDUNDANCY), PSTR(MSG_ERR_REDUNDANT_TEMP));
#endif
@ -1097,7 +1097,7 @@ void Temperature::updateTemperaturesFromRawValues() {
* a return value of 1.
*/
int8_t Temperature::widthFil_to_size_ratio() {
if (FABS(filament_width_nominal - filament_width_meas) <= FILWIDTH_ERROR_MARGIN)
if (ABS(filament_width_nominal - filament_width_meas) <= FILWIDTH_ERROR_MARGIN)
return int(100.0 * filament_width_nominal / filament_width_meas) - 100;
return 0;
}

View File

@ -91,7 +91,7 @@ enum ADCSensorState : char {
// get all oversampled sensor readings
#define MIN_ADC_ISR_LOOPS 10
#define ACTUAL_ADC_SAMPLES max(int(MIN_ADC_ISR_LOOPS), int(SensorsReady))
#define ACTUAL_ADC_SAMPLES MAX(int(MIN_ADC_ISR_LOOPS), int(SensorsReady))
#if HAS_PID_HEATING
#define PID_K2 (1.0-PID_K1)
@ -440,7 +440,7 @@ class Temperature {
#endif
target_temperature_bed =
#ifdef BED_MAXTEMP
min(celsius, BED_MAXTEMP)
MIN(celsius, BED_MAXTEMP)
#else
celsius
#endif
@ -463,7 +463,7 @@ class Temperature {
#endif
FORCE_INLINE static bool wait_for_heating(const uint8_t e) {
return degTargetHotend(e) > TEMP_HYSTERESIS && abs(degHotend(e) - degTargetHotend(e)) > TEMP_HYSTERESIS;
return degTargetHotend(e) > TEMP_HYSTERESIS && ABS(degHotend(e) - degTargetHotend(e)) > TEMP_HYSTERESIS;
}
/**