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

@ -785,79 +785,6 @@ typedef struct
//! @} //! @}
/*! \name Mathematics
*
* The same considerations as for clz and ctz apply here but GCC does not
* provide built-in functions to access the assembly instructions abs, min and
* max and it does not produce them by itself in most cases, so two sets of
* macros are defined here:
* - Abs, Min and Max to apply to constant expressions (values known at
* compile time);
* - abs, min and max to apply to non-constant expressions (values unknown at
* compile time), abs is found in stdlib.h.
*/
//! @{
/*! \brief Takes the absolute value of \a a.
*
* \param a Input value.
*
* \return Absolute value of \a a.
*
* \note More optimized if only used with values known at compile time.
*/
#define Abs(a) (((a) < 0 ) ? -(a) : (a))
/*! \brief Takes the minimal value of \a a and \a b.
*
* \param a Input value.
* \param b Input value.
*
* \return Minimal value of \a a and \a b.
*
* \note More optimized if only used with values known at compile time.
*/
#define Min(a, b) (((a) < (b)) ? (a) : (b))
/*! \brief Takes the maximal value of \a a and \a b.
*
* \param a Input value.
* \param b Input value.
*
* \return Maximal value of \a a and \a b.
*
* \note More optimized if only used with values known at compile time.
*/
#define Max(a, b) (((a) > (b)) ? (a) : (b))
// abs() is already defined by stdlib.h
/*! \brief Takes the minimal value of \a a and \a b.
*
* \param a Input value.
* \param b Input value.
*
* \return Minimal value of \a a and \a b.
*
* \note More optimized if only used with values unknown at compile time.
*/
#define min(a, b) Min(a, b)
/*! \brief Takes the maximal value of \a a and \a b.
*
* \param a Input value.
* \param b Input value.
*
* \return Maximal value of \a a and \a b.
*
* \note More optimized if only used with values unknown at compile time.
*/
#define max(a, b) Max(a, b)
//! @}
/*! \brief Calls the routine at address \a addr. /*! \brief Calls the routine at address \a addr.
* *
* It generates a long call opcode. * It generates a long call opcode.

View file

@ -1904,7 +1904,7 @@ static void udd_ep_in_sent(udd_ep_id_t ep)
ptr_src = &ptr_job->buf[ptr_job->buf_cnt]; ptr_src = &ptr_job->buf[ptr_job->buf_cnt];
nb_remain = ptr_job->buf_size - ptr_job->buf_cnt; nb_remain = ptr_job->buf_size - ptr_job->buf_cnt;
// Fill a bank even if no data (ZLP) // Fill a bank even if no data (ZLP)
nb_data = min(nb_remain, pkt_size); nb_data = MIN(nb_remain, pkt_size);
// Modify job information // Modify job information
ptr_job->buf_cnt += nb_data; ptr_job->buf_cnt += nb_data;
ptr_job->buf_load = nb_data; ptr_job->buf_load = nb_data;

View file

@ -290,7 +290,7 @@ extern "C" {
//! Bounds given integer size to allowed range and rounds it up to the nearest //! Bounds given integer size to allowed range and rounds it up to the nearest
//! available greater size, then applies register format of UOTGHS controller //! available greater size, then applies register format of UOTGHS controller
//! for endpoint size bit-field. //! for endpoint size bit-field.
#define udd_format_endpoint_size(size) (32 - clz(((uint32_t)min(max(size, 8), 1024) << 1) - 1) - 1 - 3) #define udd_format_endpoint_size(size) (32 - clz(((uint32_t)MIN(MAX(size, 8), 1024) << 1) - 1) - 1 - 3)
//! Configures the selected endpoint size //! Configures the selected endpoint size
#define udd_configure_endpoint_size(ep, size) (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPSIZE_Msk, udd_format_endpoint_size(size))) #define udd_configure_endpoint_size(ep, size) (Wr_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTCFG[0], ep), UOTGHS_DEVEPTCFG_EPSIZE_Msk, udd_format_endpoint_size(size)))
//! Gets the configured selected endpoint size //! Gets the configured selected endpoint size

View file

@ -84,7 +84,7 @@ void swSpiBegin(const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin)
uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) { uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) {
WRITE(mosi_pin, HIGH); WRITE(mosi_pin, HIGH);
WRITE(sck_pin, LOW); WRITE(sck_pin, LOW);
return (SystemCoreClock == 120000000 ? 44 : 38) / POW(2, 6 - min(spiRate, 6)); return (SystemCoreClock == 120000000 ? 44 : 38) / POW(2, 6 - MIN(spiRate, 6));
} }
#endif // TARGET_LPC1768 #endif // TARGET_LPC1768

View file

@ -50,9 +50,11 @@ typedef uint8_t byte;
#define PSTR(v) (v) #define PSTR(v) (v)
#define PGM_P const char * #define PGM_P const char *
// Used for libraries, preprocessor, and constants
#define min(a,b) ((a)<(b)?(a):(b)) #define min(a,b) ((a)<(b)?(a):(b))
#define max(a,b) ((a)>(b)?(a):(b)) #define max(a,b) ((a)>(b)?(a):(b))
#define abs(x) ((x)>0?(x):-(x)) #define abs(x) ((x)>0?(x):-(x))
#ifndef isnan #ifndef isnan
#define isnan std::isnan #define isnan std::isnan
#endif #endif
@ -60,11 +62,6 @@ typedef uint8_t byte;
#define isinf std::isinf #define isinf std::isinf
#endif #endif
//not constexpr until c++14
//#define max(v1, v2) std::max((int)v1,(int)v2)
//#define min(v1, v2) std::min((int)v1,(int)v2)
//#define abs(v) std::abs(v)
#define sq(v) ((v) * (v)) #define sq(v) ((v) * (v))
#define square(v) sq(v) #define square(v) sq(v)
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))

View file

@ -121,7 +121,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_count(STEP_TIMER_DEV, 0); timer_set_count(STEP_TIMER_DEV, 0);
timer_set_prescaler(STEP_TIMER_DEV, (uint16)(STEPPER_TIMER_PRESCALE - 1)); timer_set_prescaler(STEP_TIMER_DEV, (uint16)(STEPPER_TIMER_PRESCALE - 1));
timer_set_reload(STEP_TIMER_DEV, 0xFFFF); timer_set_reload(STEP_TIMER_DEV, 0xFFFF);
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, min(HAL_TIMER_TYPE_MAX, (HAL_STEPPER_TIMER_RATE / frequency))); timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, MIN(HAL_TIMER_TYPE_MAX, (HAL_STEPPER_TIMER_RATE / frequency)));
timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler); timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
nvic_irq_set_priority(irq_num, 1); nvic_irq_set_priority(irq_num, 1);
timer_generate_update(STEP_TIMER_DEV); timer_generate_update(STEP_TIMER_DEV);
@ -132,7 +132,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_count(TEMP_TIMER_DEV, 0); timer_set_count(TEMP_TIMER_DEV, 0);
timer_set_prescaler(TEMP_TIMER_DEV, (uint16)(TEMP_TIMER_PRESCALE - 1)); timer_set_prescaler(TEMP_TIMER_DEV, (uint16)(TEMP_TIMER_PRESCALE - 1));
timer_set_reload(TEMP_TIMER_DEV, 0xFFFF); timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, min(HAL_TIMER_TYPE_MAX, ((F_CPU / TEMP_TIMER_PRESCALE) / frequency))); timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, MIN(HAL_TIMER_TYPE_MAX, ((F_CPU / TEMP_TIMER_PRESCALE) / frequency)));
timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler); timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
nvic_irq_set_priority(irq_num, 2); nvic_irq_set_priority(irq_num, 2);
timer_generate_update(TEMP_TIMER_DEV); timer_generate_update(TEMP_TIMER_DEV);

View file

@ -130,7 +130,7 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
*/ */
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
//compare = min(compare, HAL_TIMER_TYPE_MAX); //compare = MIN(compare, HAL_TIMER_TYPE_MAX);
switch (timer_num) { switch (timer_num) {
case STEP_TIMER_NUM: case STEP_TIMER_NUM:
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, compare); timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, compare);

View file

@ -237,7 +237,7 @@ unsigned int TMC26XStepper::getSpeed(void) { return this->speed; }
*/ */
char TMC26XStepper::step(int steps_to_move) { char TMC26XStepper::step(int steps_to_move) {
if (this->steps_left == 0) { if (this->steps_left == 0) {
this->steps_left = abs(steps_to_move); // how many steps to take this->steps_left = ABS(steps_to_move); // how many steps to take
// determine direction based on whether steps_to_move is + or -: // determine direction based on whether steps_to_move is + or -:
if (steps_to_move > 0) if (steps_to_move > 0)
@ -257,7 +257,7 @@ char TMC26XStepper::move(void) {
// rem if (time >= this->next_step_time) { // rem if (time >= this->next_step_time) {
if (abs(time - this->last_step_time) > this->step_delay) { if (ABS(time - this->last_step_time) > this->step_delay) {
// increment or decrement the step number, // increment or decrement the step number,
// depending on direction: // depending on direction:
if (this->direction == 1) if (this->direction == 1)

View file

@ -99,7 +99,7 @@ int8_t Servo::attach(const int pin, const int min, const int max) {
if (pin > 0) servo_info[this->servoIndex].Pin.nbr = pin; if (pin > 0) servo_info[this->servoIndex].Pin.nbr = pin;
pinMode(servo_info[this->servoIndex].Pin.nbr, OUTPUT); // set servo pin to output pinMode(servo_info[this->servoIndex].Pin.nbr, OUTPUT); // set servo pin to output
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128 // todo min/max check: ABS(min - MIN_PULSE_WIDTH) /4 < 128
this->min = (MIN_PULSE_WIDTH - min) / 4; //resolution of min/max is 4 uS this->min = (MIN_PULSE_WIDTH - min) / 4; //resolution of min/max is 4 uS
this->max = (MAX_PULSE_WIDTH - max) / 4; this->max = (MAX_PULSE_WIDTH - max) / 4;

View file

@ -113,7 +113,7 @@
#define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+') #define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+')
#define COUNT(a) (sizeof(a)/sizeof(*a)) #define COUNT(a) (sizeof(a)/sizeof(*a))
#define ZERO(a) memset(a,0,sizeof(a)) #define ZERO(a) memset(a,0,sizeof(a))
#define COPY(a,b) memcpy(a,b,min(sizeof(a),sizeof(b))) #define COPY(a,b) memcpy(a,b,MIN(sizeof(a),sizeof(b)))
// Macros for initializing arrays // Macros for initializing arrays
#define ARRAY_6(v1, v2, v3, v4, v5, v6, ...) { v1, v2, v3, v4, v5, v6 } #define ARRAY_6(v1, v2, v3, v4, v5, v6, ...) { v1, v2, v3, v4, v5, v6 }
@ -164,12 +164,48 @@
#define CEILING(x,y) (((x) + (y) - 1) / (y)) #define CEILING(x,y) (((x) + (y) - 1) / (y))
#define MIN3(a, b, c) min(min(a, b), c) // Avoid double evaluation of arguments on MIN/MAX/ABS
#define MIN4(a, b, c, d) min(MIN3(a, b, c), d) #undef MIN
#define MIN5(a, b, c, d, e) min(MIN4(a, b, c, d), e) #undef MAX
#define MAX3(a, b, c) max(max(a, b), c) #undef ABS
#define MAX4(a, b, c, d) max(MAX3(a, b, c), d) #ifdef __cplusplus
#define MAX5(a, b, c, d, e) max(MAX4(a, b, c, d), e)
// 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
// 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
#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.000001) #define UNEAR_ZERO(x) ((x) < 0.000001)
#define NEAR_ZERO(x) WITHIN(x, -0.000001, 0.000001) #define NEAR_ZERO(x) WITHIN(x, -0.000001, 0.000001)
@ -182,7 +218,6 @@
// Maths macros that can be overridden by HAL // Maths macros that can be overridden by HAL
// //
#define ATAN2(y, x) atan2(y, x) #define ATAN2(y, x) atan2(y, x)
#define FABS(x) fabs(x)
#define POW(x, y) pow(x, y) #define POW(x, y) pow(x, y)
#define SQRT(x) sqrt(x) #define SQRT(x) sqrt(x)
#define CEIL(x) ceil(x) #define CEIL(x) ceil(x)

View file

@ -134,7 +134,7 @@ void I2CPositionEncoder::update() {
#ifdef I2CPE_EC_THRESH_PROPORTIONAL #ifdef I2CPE_EC_THRESH_PROPORTIONAL
const millis_t deltaTime = positionTime - lastPositionTime; const millis_t deltaTime = positionTime - lastPositionTime;
const uint32_t distance = abs(position - lastPosition), const uint32_t distance = ABS(position - lastPosition),
speed = distance / deltaTime; speed = distance / deltaTime;
const float threshold = constrain((speed / 50), 1, 50) * ecThreshold; const float threshold = constrain((speed / 50), 1, 50) * ecThreshold;
#else #else
@ -150,7 +150,7 @@ void I2CPositionEncoder::update() {
LOOP_L_N(i, I2CPE_ERR_ARRAY_SIZE) { LOOP_L_N(i, I2CPE_ERR_ARRAY_SIZE) {
sum += err[i]; sum += err[i];
if (i) diffSum += abs(err[i-1] - err[i]); if (i) diffSum += ABS(err[i-1] - err[i]);
} }
const int32_t error = int32_t(sum / (I2CPE_ERR_ARRAY_SIZE + 1)); //calculate average for error const int32_t error = int32_t(sum / (I2CPE_ERR_ARRAY_SIZE + 1)); //calculate average for error
@ -163,7 +163,7 @@ void I2CPositionEncoder::update() {
//SERIAL_ECHOLN(error); //SERIAL_ECHOLN(error);
#ifdef I2CPE_ERR_THRESH_ABORT #ifdef I2CPE_ERR_THRESH_ABORT
if (labs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) { if (ABS(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) {
//kill("Significant Error"); //kill("Significant Error");
SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!"); SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!");
SERIAL_ECHOLN(error); SERIAL_ECHOLN(error);
@ -175,8 +175,8 @@ void I2CPositionEncoder::update() {
if (errIdx == 0) { if (errIdx == 0) {
// In order to correct for "error" but avoid correcting for noise and non-skips // In order to correct for "error" but avoid correcting for noise and non-skips
// it must be > threshold and have a difference average of < 10 and be < 2000 steps // it must be > threshold and have a difference average of < 10 and be < 2000 steps
if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis] && if (ABS(error) > threshold * planner.axis_steps_per_mm[encoderAxis] &&
diffSum < 10 * (I2CPE_ERR_ARRAY_SIZE - 1) && labs(error) < 2000) { // Check for persistent error (skip) diffSum < 10 * (I2CPE_ERR_ARRAY_SIZE - 1) && ABS(error) < 2000) { // Check for persistent error (skip)
errPrst[errPrstIdx++] = error; // Error must persist for I2CPE_ERR_PRST_ARRAY_SIZE error cycles. This also serves to improve the average accuracy errPrst[errPrstIdx++] = error; // Error must persist for I2CPE_ERR_PRST_ARRAY_SIZE error cycles. This also serves to improve the average accuracy
if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) { if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) {
float sumP = 0; float sumP = 0;
@ -193,14 +193,14 @@ void I2CPositionEncoder::update() {
errPrstIdx = 0; errPrstIdx = 0;
} }
#else #else
if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) { if (ABS(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) {
//SERIAL_ECHOLN(error); //SERIAL_ECHOLN(error);
//SERIAL_ECHOLN(position); //SERIAL_ECHOLN(position);
thermalManager.babystepsTodo[encoderAxis] = -LROUND(error / 2); thermalManager.babystepsTodo[encoderAxis] = -LROUND(error / 2);
} }
#endif #endif
if (labs(error) > I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) { if (ABS(error) > I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) {
const millis_t ms = millis(); const millis_t ms = millis();
if (ELAPSED(ms, nextErrorCountTime)) { if (ELAPSED(ms, nextErrorCountTime)) {
SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]); SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]);
@ -258,7 +258,7 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) {
actual = mm_from_count(position); actual = mm_from_count(position);
error = actual - target; error = actual - target;
if (labs(error) > 10000) error = 0; // ? if (ABS(error) > 10000) error = 0; // ?
if (report) { if (report) {
SERIAL_ECHO(axis_codes[encoderAxis]); SERIAL_ECHO(axis_codes[encoderAxis]);
@ -293,7 +293,7 @@ int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) {
error = (encoderCountInStepperTicksScaled - target); error = (encoderCountInStepperTicksScaled - target);
//suppress discontinuities (might be caused by bad I2C readings...?) //suppress discontinuities (might be caused by bad I2C readings...?)
bool suppressOutput = (labs(error - errorPrev) > 100); bool suppressOutput = (ABS(error - errorPrev) > 100);
if (report) { if (report) {
SERIAL_ECHO(axis_codes[encoderAxis]); SERIAL_ECHO(axis_codes[encoderAxis]);
@ -435,7 +435,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
delay(250); delay(250);
stopCount = get_position(); stopCount = get_position();
travelledDistance = mm_from_count(abs(stopCount - startCount)); travelledDistance = mm_from_count(ABS(stopCount - startCount));
SERIAL_ECHOPAIR("Attempted to travel: ", travelDistance); SERIAL_ECHOPAIR("Attempted to travel: ", travelDistance);
SERIAL_ECHOLNPGM("mm."); SERIAL_ECHOLNPGM("mm.");

View file

@ -347,8 +347,8 @@ void Max7219_idle_tasks() {
NOMORE(current_depth, 16); // if the BLOCK_BUFFER_SIZE is greater than 16, two lines NOMORE(current_depth, 16); // if the BLOCK_BUFFER_SIZE is greater than 16, two lines
// of LEDs is enough to see if the buffer is draining // of LEDs is enough to see if the buffer is draining
const uint8_t st = min(current_depth, last_depth), const uint8_t st = MIN(current_depth, last_depth),
en = max(current_depth, last_depth); en = MAX(current_depth, last_depth);
if (current_depth < last_depth) if (current_depth < last_depth)
for (uint8_t i = st; i <= en; i++) // clear the highest order LEDs for (uint8_t i = st; i <= en; i++) // clear the highest order LEDs
Max7219_LED_Off(MAX7219_DEBUG_STEPPER_QUEUE + (i & 1), i / 2); Max7219_LED_Off(MAX7219_DEBUG_STEPPER_QUEUE + (i & 1), i / 2);

View file

@ -295,7 +295,7 @@ float bilinear_z_offset(const float raw[XYZ]) {
#endif #endif
gridx = gx; gridx = gx;
nextx = min(gridx + 1, ABL_BG_POINTS_X - 1); nextx = MIN(gridx + 1, ABL_BG_POINTS_X - 1);
} }
if (last_y != ry || last_gridx != gridx) { if (last_y != ry || last_gridx != gridx) {
@ -312,7 +312,7 @@ float bilinear_z_offset(const float raw[XYZ]) {
#endif #endif
gridy = gy; gridy = gy;
nexty = min(gridy + 1, ABL_BG_POINTS_Y - 1); nexty = MIN(gridy + 1, ABL_BG_POINTS_Y - 1);
} }
if (last_gridx != gridx || last_gridy != gridy) { if (last_gridx != gridx || last_gridy != gridy) {
@ -336,7 +336,7 @@ float bilinear_z_offset(const float raw[XYZ]) {
/* /*
static float last_offset = 0; static float last_offset = 0;
if (FABS(last_offset - offset) > 0.2) { if (ABS(last_offset - offset) > 0.2) {
SERIAL_ECHOPGM("Sudden Shift at "); SERIAL_ECHOPGM("Sudden Shift at ");
SERIAL_ECHOPAIR("x=", rx); SERIAL_ECHOPAIR("x=", rx);
SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]); SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]);
@ -389,7 +389,7 @@ float bilinear_z_offset(const float raw[XYZ]) {
#define LINE_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist) #define LINE_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist)
float normalized_dist, end[XYZE]; float normalized_dist, end[XYZE];
const int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2); const int8_t gcx = MAX(cx1, cx2), gcy = MAX(cy1, cy2);
// Crosses on the X and not already split on this X? // Crosses on the X and not already split on this X?
// The x_splits flags are insurance against rounding errors. // The x_splits flags are insurance against rounding errors.

View file

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

View file

@ -242,7 +242,7 @@ class unified_bed_leveling {
const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * (1.0 / (MESH_X_DIST)), const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * (1.0 / (MESH_X_DIST)),
z1 = z_values[x1_i][yi]; z1 = z_values[x1_i][yi];
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 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
// If it is, it is clamped to the last element of the // If it is, it is clamped to the last element of the
// z_values[][] array and no correction is applied. // z_values[][] array and no correction is applied.
} }
@ -276,7 +276,7 @@ class unified_bed_leveling {
const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * (1.0 / (MESH_Y_DIST)), const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * (1.0 / (MESH_Y_DIST)),
z1 = z_values[xi][y1_i]; z1 = z_values[xi][y1_i];
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 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
// If it is, it is clamped to the last element of the // If it is, it is clamped to the last element of the
// z_values[][] array and no correction is applied. // z_values[][] array and no correction is applied.
} }
@ -302,11 +302,11 @@ class unified_bed_leveling {
const float z1 = calc_z0(rx0, const float z1 = calc_z0(rx0,
mesh_index_to_xpos(cx), z_values[cx][cy], mesh_index_to_xpos(cx), z_values[cx][cy],
mesh_index_to_xpos(cx + 1), z_values[min(cx, GRID_MAX_POINTS_X - 2) + 1][cy]); mesh_index_to_xpos(cx + 1), z_values[MIN(cx, GRID_MAX_POINTS_X - 2) + 1][cy]);
const float z2 = calc_z0(rx0, const float z2 = calc_z0(rx0,
mesh_index_to_xpos(cx), z_values[cx][min(cy, GRID_MAX_POINTS_Y - 2) + 1], mesh_index_to_xpos(cx), z_values[cx][MIN(cy, GRID_MAX_POINTS_Y - 2) + 1],
mesh_index_to_xpos(cx + 1), z_values[min(cx, GRID_MAX_POINTS_X - 2) + 1][min(cy, GRID_MAX_POINTS_Y - 2) + 1]); mesh_index_to_xpos(cx + 1), z_values[MIN(cx, GRID_MAX_POINTS_X - 2) + 1][MIN(cy, GRID_MAX_POINTS_Y - 2) + 1]);
float z0 = calc_z0(ry0, float z0 = calc_z0(ry0,
mesh_index_to_ypos(cy), z1, mesh_index_to_ypos(cy), z1,

View file

@ -451,7 +451,7 @@
if (parser.seen('B')) { if (parser.seen('B')) {
g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness((float) Z_CLEARANCE_BETWEEN_PROBES); g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness((float) Z_CLEARANCE_BETWEEN_PROBES);
if (FABS(g29_card_thickness) > 1.5) { if (ABS(g29_card_thickness) > 1.5) {
SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement.");
return; return;
} }
@ -796,7 +796,7 @@
save_ubl_active_state_and_disable(); // Disable bed level correction for probing save_ubl_active_state_and_disable(); // Disable bed level correction for probing
do_blocking_move_to(0.5 * (MESH_MAX_X - (MESH_MIN_X)), 0.5 * (MESH_MAX_Y - (MESH_MIN_Y)), in_height); do_blocking_move_to(0.5 * (MESH_MAX_X - (MESH_MIN_X)), 0.5 * (MESH_MAX_Y - (MESH_MIN_Y)), in_height);
//, min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]) / 2.0); //, MIN(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]) / 2.0);
planner.synchronize(); planner.synchronize();
SERIAL_PROTOCOLPGM("Place shim under nozzle"); SERIAL_PROTOCOLPGM("Place shim under nozzle");
@ -816,7 +816,7 @@
do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES);
const float thickness = abs(z1 - z2); const float thickness = ABS(z1 - z2);
if (g29_verbose_level > 1) { if (g29_verbose_level > 1) {
SERIAL_PROTOCOLPGM("Business Card is "); SERIAL_PROTOCOLPGM("Business Card is ");
@ -1499,10 +1499,10 @@
#include "../../../libs/vector_3.h" #include "../../../libs/vector_3.h"
void unified_bed_leveling::tilt_mesh_based_on_probed_grid(const bool do_3_pt_leveling) { void unified_bed_leveling::tilt_mesh_based_on_probed_grid(const bool do_3_pt_leveling) {
constexpr int16_t x_min = max(MIN_PROBE_X, MESH_MIN_X), constexpr int16_t x_min = MAX(MIN_PROBE_X, MESH_MIN_X),
x_max = min(MAX_PROBE_X, MESH_MAX_X), x_max = MIN(MAX_PROBE_X, MESH_MAX_X),
y_min = max(MIN_PROBE_Y, MESH_MIN_Y), y_min = MAX(MIN_PROBE_Y, MESH_MIN_Y),
y_max = min(MAX_PROBE_Y, MESH_MAX_Y); y_max = MIN(MAX_PROBE_Y, MESH_MAX_Y);
bool abort_flag = false; bool abort_flag = false;
@ -1770,7 +1770,7 @@
SERIAL_ECHOPGM("Extrapolating mesh..."); SERIAL_ECHOPGM("Extrapolating mesh...");
const float weight_scaled = weight_factor * max(MESH_X_DIST, MESH_Y_DIST); const float weight_scaled = weight_factor * MAX(MESH_X_DIST, MESH_Y_DIST);
for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++)
for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++)

View file

@ -387,11 +387,11 @@
inverse_kinematics(raw); // this writes delta[ABC] from raw[XYZE] inverse_kinematics(raw); // this writes delta[ABC] from raw[XYZE]
// should move the feedrate scaling to scara inverse_kinematics // should move the feedrate scaling to scara inverse_kinematics
const float adiff = FABS(delta[A_AXIS] - scara_oldA), const float adiff = ABS(delta[A_AXIS] - scara_oldA),
bdiff = FABS(delta[B_AXIS] - scara_oldB); bdiff = ABS(delta[B_AXIS] - scara_oldB);
scara_oldA = delta[A_AXIS]; scara_oldA = delta[A_AXIS];
scara_oldB = delta[B_AXIS]; scara_oldB = delta[B_AXIS];
float s_feedrate = max(adiff, bdiff) * scara_feed_factor; float s_feedrate = MAX(adiff, bdiff) * scara_feed_factor;
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], in_raw[E_AXIS], s_feedrate, active_extruder); planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], in_raw[E_AXIS], s_feedrate, active_extruder);

View file

@ -87,7 +87,7 @@ static void i2c_send(const uint8_t channel, const byte v) {
// This is for the MCP4018 I2C based digipot // This is for the MCP4018 I2C based digipot
void digipot_i2c_set_current(const uint8_t channel, const float current) { void digipot_i2c_set_current(const uint8_t channel, const float current) {
i2c_send(channel, current_to_wiper(min(max(current, 0.0f), float(DIGIPOT_A4988_MAX_CURRENT)))); i2c_send(channel, current_to_wiper(MIN(MAX(current, 0.0f), float(DIGIPOT_A4988_MAX_CURRENT))));
} }
void digipot_i2c_init() { void digipot_i2c_init() {

View file

@ -69,7 +69,7 @@ void digipot_i2c_set_current(const uint8_t channel, const float current) {
// Set actual wiper value // Set actual wiper value
byte addresses[4] = { 0x00, 0x10, 0x60, 0x70 }; byte addresses[4] = { 0x00, 0x10, 0x60, 0x70 };
i2c_send(addr, addresses[channel & 0x3], current_to_wiper(min((float) max(current, 0.0f), DIGIPOT_I2C_MAX_CURRENT))); i2c_send(addr, addresses[channel & 0x3], current_to_wiper(MIN((float) MAX(current, 0.0f), DIGIPOT_I2C_MAX_CURRENT)));
} }
void digipot_i2c_init() { void digipot_i2c_init() {

View file

@ -305,7 +305,7 @@ void print_line_from_here_to_there(const float &sx, const float &sy, const float
// If the end point of the line is closer to the nozzle, flip the direction, // If the end point of the line is closer to the nozzle, flip the direction,
// moving from the end to the start. On very small lines the optimization isn't worth it. // moving from the end to the start. On very small lines the optimization isn't worth it.
if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < FABS(line_length)) if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length))
return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz); return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz);
// Decide whether to retract & bump // Decide whether to retract & bump
@ -427,7 +427,7 @@ inline bool turn_on_heaters() {
#endif #endif
#endif #endif
thermalManager.setTargetBed(g26_bed_temp); thermalManager.setTargetBed(g26_bed_temp);
while (abs(thermalManager.degBed() - g26_bed_temp) > 3) { while (ABS(thermalManager.degBed() - g26_bed_temp) > 3) {
#if ENABLED(NEWPANEL) #if ENABLED(NEWPANEL)
if (is_lcd_clicked()) return exit_from_g26(); if (is_lcd_clicked()) return exit_from_g26();
@ -450,7 +450,7 @@ inline bool turn_on_heaters() {
// Start heating the nozzle and wait for it to reach temperature. // Start heating the nozzle and wait for it to reach temperature.
thermalManager.setTargetHotend(g26_hotend_temp, 0); thermalManager.setTargetHotend(g26_hotend_temp, 0);
while (abs(thermalManager.degHotend(0) - g26_hotend_temp) > 3) { while (ABS(thermalManager.degHotend(0) - g26_hotend_temp) > 3) {
#if ENABLED(NEWPANEL) #if ENABLED(NEWPANEL)
if (is_lcd_clicked()) return exit_from_g26(); if (is_lcd_clicked()) return exit_from_g26();

View file

@ -471,7 +471,7 @@ void GcodeSuite::G29() {
if (verbose_level || seenQ) { if (verbose_level || seenQ) {
SERIAL_PROTOCOLPGM("Manual G29 "); SERIAL_PROTOCOLPGM("Manual G29 ");
if (g29_in_progress) { if (g29_in_progress) {
SERIAL_PROTOCOLPAIR("point ", min(abl_probe_index + 1, abl_points)); SERIAL_PROTOCOLPAIR("point ", MIN(abl_probe_index + 1, abl_points));
SERIAL_PROTOCOLLNPAIR(" of ", abl_points); SERIAL_PROTOCOLLNPAIR(" of ", abl_points);
} }
else else

View file

@ -205,7 +205,7 @@ void GcodeSuite::G29() {
} // switch(state) } // switch(state)
if (state == MeshNext) { if (state == MeshNext) {
SERIAL_PROTOCOLPAIR("MBL G29 point ", min(mbl_probe_index, GRID_MAX_POINTS)); SERIAL_PROTOCOLPAIR("MBL G29 point ", MIN(mbl_probe_index, GRID_MAX_POINTS));
SERIAL_PROTOCOLLNPAIR(" of ", int(GRID_MAX_POINTS)); SERIAL_PROTOCOLLNPAIR(" of ", int(GRID_MAX_POINTS));
} }

View file

@ -64,7 +64,7 @@
const float mlx = max_length(X_AXIS), const float mlx = max_length(X_AXIS),
mly = max_length(Y_AXIS), mly = max_length(Y_AXIS),
mlratio = mlx > mly ? mly / mlx : mlx / mly, mlratio = mlx > mly ? mly / mlx : mlx / mly,
fr_mm_s = min(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0); fr_mm_s = MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0);
#if ENABLED(SENSORLESS_HOMING) #if ENABLED(SENSORLESS_HOMING)
sensorless_homing_per_axis(X_AXIS); sensorless_homing_per_axis(X_AXIS);

View file

@ -129,7 +129,7 @@ void GcodeSuite::M48() {
(int) (0.1250000000 * (DELTA_PRINTABLE_RADIUS)), (int) (0.1250000000 * (DELTA_PRINTABLE_RADIUS)),
(int) (0.3333333333 * (DELTA_PRINTABLE_RADIUS)) (int) (0.3333333333 * (DELTA_PRINTABLE_RADIUS))
#else #else
(int) 5.0, (int) (0.125 * min(X_BED_SIZE, Y_BED_SIZE)) (int) 5.0, (int) (0.125 * MIN(X_BED_SIZE, Y_BED_SIZE))
#endif #endif
); );

View file

@ -50,7 +50,7 @@
case DXC_AUTO_PARK_MODE: case DXC_AUTO_PARK_MODE:
break; break;
case DXC_DUPLICATION_MODE: case DXC_DUPLICATION_MODE:
if (parser.seen('X')) duplicate_extruder_x_offset = max(parser.value_linear_units(), X2_MIN_POS - x_home_pos(0)); if (parser.seen('X')) duplicate_extruder_x_offset = MAX(parser.value_linear_units(), X2_MIN_POS - x_home_pos(0));
if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff(); if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff();
SERIAL_ECHO_START(); SERIAL_ECHO_START();
SERIAL_ECHOPGM(MSG_HOTEND_OFFSET); SERIAL_ECHOPGM(MSG_HOTEND_OFFSET);

View file

@ -50,7 +50,7 @@
*/ */
void GcodeSuite::M125() { void GcodeSuite::M125() {
// Initial retract before move to filament change position // Initial retract before move to filament change position
const float retract = -FABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0
#ifdef PAUSE_PARK_RETRACT_LENGTH #ifdef PAUSE_PARK_RETRACT_LENGTH
+ (PAUSE_PARK_RETRACT_LENGTH) + (PAUSE_PARK_RETRACT_LENGTH)
#endif #endif

View file

@ -74,7 +74,7 @@ void GcodeSuite::M600() {
#endif #endif
// Initial retract before move to filament change position // Initial retract before move to filament change position
const float retract = -FABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0 const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0
#ifdef PAUSE_PARK_RETRACT_LENGTH #ifdef PAUSE_PARK_RETRACT_LENGTH
+ (PAUSE_PARK_RETRACT_LENGTH) + (PAUSE_PARK_RETRACT_LENGTH)
#endif #endif
@ -93,14 +93,14 @@ void GcodeSuite::M600() {
#endif #endif
// Unload filament // Unload filament
const float unload_length = -FABS(parser.seen('U') ? parser.value_axis_units(E_AXIS) const float unload_length = -ABS(parser.seen('U') ? parser.value_axis_units(E_AXIS)
: filament_change_unload_length[active_extruder]); : filament_change_unload_length[active_extruder]);
// Slow load filament // Slow load filament
constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH; constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
// Fast load filament // Fast load filament
const float fast_load_length = FABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS)
: filament_change_load_length[active_extruder]); : filament_change_load_length[active_extruder]);
const int beep_count = parser.intval('B', const int beep_count = parser.intval('B',

View file

@ -47,7 +47,7 @@ void GcodeSuite::M603() {
// Unload length // Unload length
if (parser.seen('U')) { if (parser.seen('U')) {
filament_change_unload_length[target_extruder] = FABS(parser.value_axis_units(E_AXIS)); filament_change_unload_length[target_extruder] = ABS(parser.value_axis_units(E_AXIS));
#if ENABLED(PREVENT_LENGTHY_EXTRUDE) #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
NOMORE(filament_change_unload_length[target_extruder], EXTRUDE_MAXLENGTH); NOMORE(filament_change_unload_length[target_extruder], EXTRUDE_MAXLENGTH);
#endif #endif
@ -55,7 +55,7 @@ void GcodeSuite::M603() {
// Load length // Load length
if (parser.seen('L')) { if (parser.seen('L')) {
filament_change_load_length[target_extruder] = FABS(parser.value_axis_units(E_AXIS)); filament_change_load_length[target_extruder] = ABS(parser.value_axis_units(E_AXIS));
#if ENABLED(PREVENT_LENGTHY_EXTRUDE) #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
NOMORE(filament_change_load_length[target_extruder], EXTRUDE_MAXLENGTH); NOMORE(filament_change_load_length[target_extruder], EXTRUDE_MAXLENGTH);
#endif #endif

View file

@ -74,18 +74,18 @@ void GcodeSuite::M701() {
// Lift Z axis // Lift Z axis
if (park_point.z > 0) if (park_point.z > 0)
do_blocking_move_to_z(min(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE); do_blocking_move_to_z(MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE);
// Load filament // Load filament
constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH; constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
const float fast_load_length = FABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS)
: filament_change_load_length[active_extruder]); : filament_change_load_length[active_extruder]);
load_filament(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH, FILAMENT_CHANGE_ALERT_BEEPS, load_filament(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH, FILAMENT_CHANGE_ALERT_BEEPS,
true, thermalManager.wait_for_heating(target_extruder), ADVANCED_PAUSE_MODE_LOAD_FILAMENT); true, thermalManager.wait_for_heating(target_extruder), ADVANCED_PAUSE_MODE_LOAD_FILAMENT);
// Restore Z axis // Restore Z axis
if (park_point.z > 0) if (park_point.z > 0)
do_blocking_move_to_z(max(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE); do_blocking_move_to_z(MAX(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE);
#if EXTRUDERS > 1 #if EXTRUDERS > 1
// Restore toolhead if it was changed // Restore toolhead if it was changed
@ -136,7 +136,7 @@ void GcodeSuite::M702() {
// Lift Z axis // Lift Z axis
if (park_point.z > 0) if (park_point.z > 0)
do_blocking_move_to_z(min(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE); do_blocking_move_to_z(MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), NOZZLE_PARK_Z_FEEDRATE);
// Unload filament // Unload filament
#if EXTRUDERS > 1 && ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) #if EXTRUDERS > 1 && ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS)
@ -150,7 +150,7 @@ void GcodeSuite::M702() {
#endif #endif
{ {
// Unload length // Unload length
const float unload_length = -FABS(parser.seen('U') ? parser.value_axis_units(E_AXIS) : const float unload_length = -ABS(parser.seen('U') ? parser.value_axis_units(E_AXIS) :
filament_change_unload_length[target_extruder]); filament_change_unload_length[target_extruder]);
unload_filament(unload_length, true, ADVANCED_PAUSE_MODE_UNLOAD_FILAMENT); unload_filament(unload_length, true, ADVANCED_PAUSE_MODE_UNLOAD_FILAMENT);
@ -158,7 +158,7 @@ void GcodeSuite::M702() {
// Restore Z axis // Restore Z axis
if (park_point.z > 0) if (park_point.z > 0)
do_blocking_move_to_z(max(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE); do_blocking_move_to_z(MAX(current_position[Z_AXIS] - park_point.z, 0), NOZZLE_PARK_Z_FEEDRATE);
#if EXTRUDERS > 1 #if EXTRUDERS > 1
// Restore toolhead if it was changed // Restore toolhead if it was changed

View file

@ -61,7 +61,7 @@ void GcodeSuite::G0_G1(
if (fwretract.autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { if (fwretract.autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) {
const float echange = destination[E_AXIS] - current_position[E_AXIS]; const float echange = destination[E_AXIS] - current_position[E_AXIS];
// Is this a retract or recover move? // Is this a retract or recover move?
if (WITHIN(FABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) {
current_position[E_AXIS] = destination[E_AXIS]; // Hide a G1-based retract/recover from calculations current_position[E_AXIS] = destination[E_AXIS]; // Hide a G1-based retract/recover from calculations
sync_plan_position_e(); // AND from the planner sync_plan_position_e(); // AND from the planner
return fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) return fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored)

View file

@ -91,7 +91,7 @@ void plan_arc(
angular_travel = RADIANS(360); angular_travel = RADIANS(360);
const float flat_mm = radius * angular_travel, const float flat_mm = radius * angular_travel,
mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : FABS(flat_mm); mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm);
if (mm_of_travel < 0.001) return; if (mm_of_travel < 0.001) return;
uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT)); uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT));

View file

@ -39,8 +39,8 @@ static bool G38_run_probe() {
// Get direction of move and retract // Get direction of move and retract
float retract_mm[XYZ]; float retract_mm[XYZ];
LOOP_XYZ(i) { LOOP_XYZ(i) {
float dist = destination[i] - current_position[i]; const float dist = destination[i] - current_position[i];
retract_mm[i] = FABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1); retract_mm[i] = ABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1);
} }
#endif #endif
@ -105,7 +105,7 @@ void GcodeSuite::G38(const bool is_38_2) {
// If any axis has enough movement, do the move // If any axis has enough movement, do the move
LOOP_XYZ(i) LOOP_XYZ(i)
if (FABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) { if (ABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) {
if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate((AxisEnum)i); if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate((AxisEnum)i);
// If G38.2 fails throw an error // If G38.2 fails throw an error
if (!G38_run_probe() && is_38_2) { if (!G38_run_probe() && is_38_2) {

View file

@ -216,7 +216,7 @@ void GcodeSuite::M109() {
#if TEMP_RESIDENCY_TIME > 0 #if TEMP_RESIDENCY_TIME > 0
const float temp_diff = FABS(target_temp - temp); const float temp_diff = ABS(target_temp - temp);
if (!residency_start_ms) { if (!residency_start_ms) {
// Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time. // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time.

View file

@ -55,14 +55,14 @@ void GcodeSuite::M106() {
fanSpeeds[p] = new_fanSpeeds[p]; fanSpeeds[p] = new_fanSpeeds[p];
break; break;
default: default:
new_fanSpeeds[p] = min(t, 255); new_fanSpeeds[p] = MIN(t, 255);
break; break;
} }
return; return;
} }
#endif // EXTRA_FAN_SPEED #endif // EXTRA_FAN_SPEED
const uint16_t s = parser.ushortval('S', 255); const uint16_t s = parser.ushortval('S', 255);
fanSpeeds[p] = min(s, 255); fanSpeeds[p] = MIN(s, 255U);
} }
} }

View file

@ -145,7 +145,7 @@ void GcodeSuite::M190() {
#if TEMP_BED_RESIDENCY_TIME > 0 #if TEMP_BED_RESIDENCY_TIME > 0
const float temp_diff = FABS(target_temp - temp); const float temp_diff = ABS(target_temp - temp);
if (!residency_start_ms) { if (!residency_start_ms) {
// Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time. // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time.

View file

@ -35,6 +35,16 @@
|| MB(SCOOVO_X9H) \ || MB(SCOOVO_X9H) \
) )
#ifdef TEENSYDUINO
#undef max
#define max(a,b) ((a)>(b)?(a):(b))
#undef min
#define min(a,b) ((a)<(b)?(a):(b))
#undef NOT_A_PIN // Override Teensyduino legacy CapSense define work-around
#define NOT_A_PIN 0 // For PINS_DEBUGGING
#endif
#define IS_SCARA (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA)) #define IS_SCARA (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA))
#define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA) #define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
#define IS_CARTESIAN !IS_KINEMATIC #define IS_CARTESIAN !IS_KINEMATIC
@ -1374,7 +1384,6 @@
#undef LROUND #undef LROUND
#undef FMOD #undef FMOD
#define ATAN2(y, x) atan2f(y, x) #define ATAN2(y, x) atan2f(y, x)
#define FABS(x) fabsf(x)
#define POW(x, y) powf(x, y) #define POW(x, y) powf(x, y)
#define SQRT(x) sqrtf(x) #define SQRT(x) sqrtf(x)
#define CEIL(x) ceilf(x) #define CEIL(x) ceilf(x)
@ -1383,16 +1392,6 @@
#define FMOD(x, y) fmodf(x, y) #define FMOD(x, y) fmodf(x, y)
#endif #endif
#ifdef TEENSYDUINO
#undef max
#define max(a,b) ((a)>(b)?(a):(b))
#undef min
#define min(a,b) ((a)<(b)?(a):(b))
#undef NOT_A_PIN // Override Teensyduino legacy CapSense define work-around
#define NOT_A_PIN 0 // For PINS_DEBUGGING
#endif
// Number of VFAT entries used. Each entry has 13 UTF-16 characters // Number of VFAT entries used. Each entry has 13 UTF-16 characters
#if ENABLED(SCROLL_LONG_FILENAMES) #if ENABLED(SCROLL_LONG_FILENAMES)
#define MAX_VFAT_ENTRIES (5) #define MAX_VFAT_ENTRIES (5)

View file

@ -75,7 +75,7 @@ int inbound_count;
// Everything written needs the high bit set. // Everything written needs the high bit set.
void write_to_lcd_P(const char * const message) { void write_to_lcd_P(const char * const message) {
char encoded_message[MAX_CURLY_COMMAND]; char encoded_message[MAX_CURLY_COMMAND];
uint8_t message_length = min(strlen_P(message), sizeof(encoded_message)); uint8_t message_length = MIN(strlen_P(message), sizeof(encoded_message));
for (uint8_t i = 0; i < message_length; i++) for (uint8_t i = 0; i < message_length; i++)
encoded_message[i] = pgm_read_byte(&message[i]) | 0x80; encoded_message[i] = pgm_read_byte(&message[i]) | 0x80;
@ -85,7 +85,7 @@ void write_to_lcd_P(const char * const message) {
void write_to_lcd(const char * const message) { void write_to_lcd(const char * const message) {
char encoded_message[MAX_CURLY_COMMAND]; char encoded_message[MAX_CURLY_COMMAND];
const uint8_t message_length = min(strlen(message), sizeof(encoded_message)); const uint8_t message_length = MIN(strlen(message), sizeof(encoded_message));
for (uint8_t i = 0; i < message_length; i++) for (uint8_t i = 0; i < message_length; i++)
encoded_message[i] = message[i] | 0x80; encoded_message[i] = message[i] | 0x80;

View file

@ -629,7 +629,7 @@ uint16_t max_display_update_time = 0;
screen_changed = false; screen_changed = false;
} }
if (screen_items > 0 && encoderLine >= screen_items - limit) { if (screen_items > 0 && encoderLine >= screen_items - limit) {
encoderLine = max(0, screen_items - limit); encoderLine = MAX(0, screen_items - limit);
encoderPosition = encoderLine * (ENCODER_STEPS_PER_MENU_ITEM); encoderPosition = encoderLine * (ENCODER_STEPS_PER_MENU_ITEM);
} }
if (is_menu) { if (is_menu) {
@ -1579,7 +1579,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
* *
*/ */
void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const int16_t fan) { void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const int16_t fan) {
if (temph > 0) thermalManager.setTargetHotend(min(heater_maxtemp[endnum], temph), endnum); if (temph > 0) thermalManager.setTargetHotend(MIN(heater_maxtemp[endnum], temph), endnum);
#if HAS_HEATED_BED #if HAS_HEATED_BED
if (tempb >= 0) thermalManager.setTargetBed(tempb); if (tempb >= 0) thermalManager.setTargetBed(tempb);
#else #else
@ -2118,7 +2118,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
char UBL_LCD_GCODE[16]; char UBL_LCD_GCODE[16];
const int ind = ubl_height_amount > 0 ? 9 : 10; const int ind = ubl_height_amount > 0 ? 9 : 10;
strcpy_P(UBL_LCD_GCODE, PSTR("G29 P6 C -")); strcpy_P(UBL_LCD_GCODE, PSTR("G29 P6 C -"));
sprintf_P(&UBL_LCD_GCODE[ind], PSTR(".%i"), abs(ubl_height_amount)); sprintf_P(&UBL_LCD_GCODE[ind], PSTR(".%i"), ABS(ubl_height_amount));
lcd_enqueue_command(UBL_LCD_GCODE); lcd_enqueue_command(UBL_LCD_GCODE);
} }
@ -2441,7 +2441,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
if (encoderPosition) { if (encoderPosition) {
step_scaler += (int32_t)encoderPosition; step_scaler += (int32_t)encoderPosition;
x_plot += step_scaler / (ENCODER_STEPS_PER_MENU_ITEM); x_plot += step_scaler / (ENCODER_STEPS_PER_MENU_ITEM);
if (abs(step_scaler) >= ENCODER_STEPS_PER_MENU_ITEM) step_scaler = 0; if (ABS(step_scaler) >= ENCODER_STEPS_PER_MENU_ITEM) step_scaler = 0;
encoderPosition = 0; encoderPosition = 0;
lcdDrawUpdate = LCDVIEW_REDRAW_NOW; lcdDrawUpdate = LCDVIEW_REDRAW_NOW;
} }
@ -2853,7 +2853,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
do_blocking_move_to_xy(rx, ry); do_blocking_move_to_xy(rx, ry);
lcd_synchronize(); lcd_synchronize();
move_menu_scale = max(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / float(DEFAULT_XYZ_STEPS_PER_UNIT)); move_menu_scale = MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / float(DEFAULT_XYZ_STEPS_PER_UNIT));
lcd_goto_screen(lcd_move_z); lcd_goto_screen(lcd_move_z);
} }
@ -3625,8 +3625,8 @@ void lcd_quick_feedback(const bool clear_buttons) {
#define MINTEMP_ALL MIN3(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP) #define MINTEMP_ALL MIN3(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 MAX3(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)
#else #else
#define MINTEMP_ALL HEATER_0_MINTEMP #define MINTEMP_ALL HEATER_0_MINTEMP
#define MAXTEMP_ALL HEATER_0_MAXTEMP #define MAXTEMP_ALL HEATER_0_MAXTEMP
@ -5229,7 +5229,7 @@ void lcd_update() {
#endif #endif
const bool encoderPastThreshold = (abs(encoderDiff) >= ENCODER_PULSES_PER_STEP); const bool encoderPastThreshold = (ABS(encoderDiff) >= ENCODER_PULSES_PER_STEP);
if (encoderPastThreshold || lcd_clicked) { if (encoderPastThreshold || lcd_clicked) {
if (encoderPastThreshold) { if (encoderPastThreshold) {
int32_t encoderMultiplier = 1; int32_t encoderMultiplier = 1;
@ -5237,7 +5237,7 @@ void lcd_update() {
#if ENABLED(ENCODER_RATE_MULTIPLIER) #if ENABLED(ENCODER_RATE_MULTIPLIER)
if (encoderRateMultiplierEnabled) { if (encoderRateMultiplierEnabled) {
int32_t encoderMovementSteps = abs(encoderDiff) / ENCODER_PULSES_PER_STEP; int32_t encoderMovementSteps = ABS(encoderDiff) / ENCODER_PULSES_PER_STEP;
if (lastEncoderMovementMillis) { if (lastEncoderMovementMillis) {
// Note that the rate is always calculated between two passes through the // Note that the rate is always calculated between two passes through the

View file

@ -534,7 +534,7 @@ void lcd_implementation_clear() { } // Automatically cleared by Picture Loop
name_hash = ((name_hash << 1) | (name_hash >> 7)) ^ filename[l]; // rotate, xor name_hash = ((name_hash << 1) | (name_hash >> 7)) ^ filename[l]; // rotate, xor
if (filename_scroll_hash != name_hash) { // If the hash changed... if (filename_scroll_hash != name_hash) { // If the hash changed...
filename_scroll_hash = name_hash; // Save the new hash filename_scroll_hash = name_hash; // Save the new hash
filename_scroll_max = max(0, utf8_strlen(longFilename) - maxlen); // Update the scroll limit filename_scroll_max = MAX(0, utf8_strlen(longFilename) - maxlen); // Update the scroll limit
filename_scroll_pos = 0; // Reset scroll to the start filename_scroll_pos = 0; // Reset scroll to the start
lcd_status_update_delay = 8; // Don't scroll right away lcd_status_update_delay = 8; // Don't scroll right away
} }

View file

@ -352,12 +352,12 @@ void lcd_implementation_clear() { lcd.clear(); }
lcd_put_u8str(text); lcd_put_u8str(text);
#else #else
char tmp[LCD_WIDTH + 1] = {0}; char tmp[LCD_WIDTH + 1] = {0};
int16_t n = max(utf8_strlen_P(text) - len, 0); int16_t n = MAX(utf8_strlen_P(text) - len, 0);
for (int16_t i = 0; i <= n; i++) { for (int16_t i = 0; i <= n; i++) {
utf8_strncpy_p(tmp, text + i, min(len, LCD_WIDTH)); utf8_strncpy_p(tmp, text + i, MIN(len, LCD_WIDTH));
lcd_moveto(col, line); lcd_moveto(col, line);
lcd_put_u8str(tmp); lcd_put_u8str(tmp);
delay(time / max(n, 1)); delay(time / MAX(n, 1));
} }
#endif #endif
} }
@ -875,7 +875,7 @@ static void lcd_implementation_status_screen() {
name_hash = ((name_hash << 1) | (name_hash >> 7)) ^ filename[l]; // rotate, xor name_hash = ((name_hash << 1) | (name_hash >> 7)) ^ filename[l]; // rotate, xor
if (filename_scroll_hash != name_hash) { // If the hash changed... if (filename_scroll_hash != name_hash) { // If the hash changed...
filename_scroll_hash = name_hash; // Save the new hash filename_scroll_hash = name_hash; // Save the new hash
filename_scroll_max = max(0, utf8_strlen(longFilename) - n); // Update the scroll limit filename_scroll_max = MAX(0, utf8_strlen(longFilename) - n); // Update the scroll limit
filename_scroll_pos = 0; // Reset scroll to the start filename_scroll_pos = 0; // Reset scroll to the start
lcd_status_update_delay = 8; // Don't scroll right away lcd_status_update_delay = 8; // Don't scroll right away
} }
@ -1186,7 +1186,7 @@ static void lcd_implementation_status_screen() {
//dump_custom_char("at entry:", &new_char); //dump_custom_char("at entry:", &new_char);
clear_custom_char(&new_char); clear_custom_char(&new_char);
const uint8_t ypix = min(upper_left.y_pixel_offset + pixels_per_y_mesh_pnt, ULTRA_Y_PIXELS_PER_CHAR); const uint8_t ypix = MIN(upper_left.y_pixel_offset + pixels_per_y_mesh_pnt, ULTRA_Y_PIXELS_PER_CHAR);
for (j = upper_left.y_pixel_offset; j < ypix; j++) { for (j = upper_left.y_pixel_offset; j < ypix; j++) {
i = upper_left.x_pixel_mask; i = upper_left.x_pixel_mask;
for (k = 0; k < pixels_per_x_mesh_pnt; k++) { for (k = 0; k < pixels_per_x_mesh_pnt; k++) {

View file

@ -58,7 +58,7 @@ int finish_incremental_LSF(struct linear_fit_data *lsf) {
lsf->xzbar = lsf->xzbar / N - lsf->xbar * lsf->zbar; lsf->xzbar = lsf->xzbar / N - lsf->xbar * lsf->zbar;
const float DD = lsf->x2bar * lsf->y2bar - sq(lsf->xybar); const float DD = lsf->x2bar * lsf->y2bar - sq(lsf->xybar);
if (FABS(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy)) if (ABS(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy))
return 1; return 1;
lsf->A = (lsf->yzbar * lsf->xybar - lsf->xzbar * lsf->y2bar) / DD; lsf->A = (lsf->yzbar * lsf->xybar - lsf->xzbar * lsf->y2bar) / DD;

View file

@ -63,8 +63,8 @@ void inline incremental_WLSF(struct linear_fit_data *lsf, const float &x, const
lsf->xzbar += w * x * z; lsf->xzbar += w * x * z;
lsf->yzbar += w * y * z; lsf->yzbar += w * y * z;
lsf->N += w; lsf->N += w;
lsf->max_absx = max(FABS(w * x), lsf->max_absx); lsf->max_absx = MAX(ABS(w * x), lsf->max_absx);
lsf->max_absy = max(FABS(w * y), lsf->max_absy); lsf->max_absy = MAX(ABS(w * y), lsf->max_absy);
} }
void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) { void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) {
@ -77,8 +77,8 @@ void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const f
lsf->xybar += x * y; lsf->xybar += x * y;
lsf->xzbar += x * z; lsf->xzbar += x * z;
lsf->yzbar += y * z; lsf->yzbar += y * z;
lsf->max_absx = max(FABS(x), lsf->max_absx); lsf->max_absx = MAX(ABS(x), lsf->max_absx);
lsf->max_absy = max(FABS(y), lsf->max_absy); lsf->max_absy = MAX(ABS(y), lsf->max_absy);
lsf->N += 1.0; lsf->N += 1.0;
} }

View file

@ -79,7 +79,7 @@
do_blocking_move_to(start.x, start.y, start.z); do_blocking_move_to(start.x, start.y, start.z);
const uint8_t zigs = objects << 1; const uint8_t zigs = objects << 1;
const bool horiz = FABS(diffx) >= FABS(diffy); // Do a horizontal wipe? const bool horiz = ABS(diffx) >= ABS(diffy); // Do a horizontal wipe?
const float P = (horiz ? diffx : diffy) / zigs; // Period of each zig / zag const float P = (horiz ? diffx : diffy) / zigs; // Period of each zig / zag
const point_t *side; const point_t *side;
for (uint8_t j = 0; j < strokes; j++) { for (uint8_t j = 0; j < strokes; j++) {
@ -172,11 +172,11 @@
break; break;
case 2: // Raise by Z-park height case 2: // Raise by Z-park height
do_blocking_move_to_z(min(current_position[Z_AXIS] + park.z, Z_MAX_POS), fr_z); do_blocking_move_to_z(MIN(current_position[Z_AXIS] + park.z, Z_MAX_POS), fr_z);
break; break;
default: // Raise to at least the Z-park height default: // Raise to at least the Z-park height
do_blocking_move_to_z(max(park.z, current_position[Z_AXIS]), fr_z); do_blocking_move_to_z(MAX(park.z, current_position[Z_AXIS]), fr_z);
} }
do_blocking_move_to_xy(park.x, park.y, fr_xy); do_blocking_move_to_xy(park.x, park.y, fr_xy);

View file

@ -150,7 +150,7 @@ float delta_safe_distance_from_top() {
float centered_extent = delta[A_AXIS]; float centered_extent = delta[A_AXIS];
cartesian[Y_AXIS] = DELTA_PRINTABLE_RADIUS; cartesian[Y_AXIS] = DELTA_PRINTABLE_RADIUS;
inverse_kinematics(cartesian); 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)); float cartesian_mm = SQRT(sq(xdiff) + sq(ydiff) + sq(zdiff));
// If the move is very short, check the E move distance // 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. // No E move either? Game over.
if (UNEAR_ZERO(cartesian_mm)) return true; 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); const float diff2 = HYPOT2(delta[A_AXIS] - oldA, delta[B_AXIS] - oldB);
if (diff2) { if (diff2) {
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], rtarget[Z_AXIS], rtarget[E_AXIS], SQRT(diff2) * inverse_secs, active_extruder); 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("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); 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 // If the move is very short, check the E move distance
// No E move either? Game over. // No E move either? Game over.
float cartesian_mm = SQRT(sq(xdiff) + sq(ydiff) + sq(zdiff)); 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; if (UNEAR_ZERO(cartesian_mm)) return;
// The length divided by the segment size // The length divided by the segment size
@ -921,7 +922,7 @@ void prepare_move_to_destination() {
} }
#endif // PREVENT_COLD_EXTRUSION #endif // PREVENT_COLD_EXTRUSION
#if ENABLED(PREVENT_LENGTHY_EXTRUDE) #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 current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part
SERIAL_ECHO_START(); SERIAL_ECHO_START();
SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP); SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
@ -1289,7 +1290,7 @@ void homeaxis(const AxisEnum axis) {
// When homing Z with probe respect probe clearance // When homing Z with probe respect probe clearance
const float bump = axis_home_dir * ( const float bump = axis_home_dir * (
#if HOMING_Z_WITH_PROBE #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 #endif
home_bump_mm(axis) home_bump_mm(axis)
); );
@ -1318,7 +1319,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
if (axis == X_AXIS) { if (axis == X_AXIS) {
const bool lock_x1 = pos_dir ? (endstops.x_endstop_adj > 0) : (endstops.x_endstop_adj < 0); 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 (pos_dir) adj = -adj;
if (lock_x1) stepper.set_x_lock(true); else stepper.set_x2_lock(true); if (lock_x1) stepper.set_x_lock(true); else stepper.set_x2_lock(true);
do_homing_move(axis, adj); do_homing_move(axis, adj);
@ -1329,7 +1330,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
if (axis == Y_AXIS) { if (axis == Y_AXIS) {
const bool lock_y1 = pos_dir ? (endstops.y_endstop_adj > 0) : (endstops.y_endstop_adj < 0); 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 (pos_dir) adj = -adj;
if (lock_y1) stepper.set_y_lock(true); else stepper.set_y2_lock(true); if (lock_y1) stepper.set_y_lock(true); else stepper.set_y2_lock(true);
do_homing_move(axis, adj); do_homing_move(axis, adj);
@ -1340,7 +1341,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(Z_DUAL_ENDSTOPS) #if ENABLED(Z_DUAL_ENDSTOPS)
if (axis == Z_AXIS) { if (axis == Z_AXIS) {
const bool lock_z1 = pos_dir ? (endstops.z_endstop_adj > 0) : (endstops.z_endstop_adj < 0); 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 (pos_dir) adj = -adj;
if (lock_z1) stepper.set_z_lock(true); else stepper.set_z2_lock(true); if (lock_z1) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
do_homing_move(axis, adj); do_homing_move(axis, adj);
@ -1424,7 +1425,7 @@ void homeaxis(const AxisEnum axis) {
if (axis == X_AXIS) { if (axis == X_AXIS) {
// In Dual X mode hotend_offset[X] is T1's home position // 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) { if (active_extruder != 0) {
// T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger) // 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 // 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 // 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_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 { else {
// In other modes, T0 can move from X_MIN_POS to X_MAX_POS // 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 X_AXIS:
case Y_AXIS: case Y_AXIS:
// Get a minimum radius for clamping // 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); soft_endstop_radius_2 = sq(soft_endstop_radius);
break; break;
#endif #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. // 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) { 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)) 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 #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. // 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) const float new_entry_speed = (TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH) || max_entry_speed <= next->entry_speed)
? max_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) { if (new_entry_speed != current->entry_speed) {
current->entry_speed = new_entry_speed; current->entry_speed = new_entry_speed;
SBI(current->flag, BLOCK_BIT_RECALCULATE); 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. // 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) const float new_entry_speed = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
? max_entry_speed ? 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) { if (current->entry_speed != new_entry_speed) {
current->entry_speed = new_entry_speed; current->entry_speed = new_entry_speed;
SBI(current->flag, BLOCK_BIT_RECALCULATE); 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. // guaranteed to be reached. No need to recheck.
if (!TEST(previous->flag, BLOCK_BIT_NOMINAL_LENGTH)) { if (!TEST(previous->flag, BLOCK_BIT_NOMINAL_LENGTH)) {
if (previous->entry_speed < current->entry_speed) { 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 // Check for junction speed change
if (current->entry_speed != new_entry_speed) { if (current->entry_speed != new_entry_speed) {
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 #endif // PREVENT_COLD_EXTRUSION
#if ENABLED(PREVENT_LENGTHY_EXTRUDE) #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 position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part
#if HAS_POSITION_FLOAT #if HAS_POSITION_FLOAT
position_float[E_AXIS] = target_float[E_AXIS]; 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); if (de < 0) SBI(dm, E_AXIS);
const float esteps_float = de * e_factor[extruder]; 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 // Wait for the next available block
uint8_t next_buffer_head; uint8_t next_buffer_head;
@ -1440,26 +1440,26 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
// Number of steps for each axis // Number of steps for each axis
// See http://www.corexy.com/theory.html // See http://www.corexy.com/theory.html
#if CORE_IS_XY #if CORE_IS_XY
block->steps[A_AXIS] = labs(da + db); block->steps[A_AXIS] = ABS(da + db);
block->steps[B_AXIS] = labs(da - db); block->steps[B_AXIS] = ABS(da - db);
block->steps[Z_AXIS] = labs(dc); block->steps[Z_AXIS] = ABS(dc);
#elif CORE_IS_XZ #elif CORE_IS_XZ
block->steps[A_AXIS] = labs(da + dc); block->steps[A_AXIS] = ABS(da + dc);
block->steps[Y_AXIS] = labs(db); block->steps[Y_AXIS] = ABS(db);
block->steps[C_AXIS] = labs(da - dc); block->steps[C_AXIS] = ABS(da - dc);
#elif CORE_IS_YZ #elif CORE_IS_YZ
block->steps[X_AXIS] = labs(da); block->steps[X_AXIS] = ABS(da);
block->steps[B_AXIS] = labs(db + dc); block->steps[B_AXIS] = ABS(db + dc);
block->steps[C_AXIS] = labs(db - dc); block->steps[C_AXIS] = ABS(db - dc);
#elif IS_SCARA #elif IS_SCARA
block->steps[A_AXIS] = labs(da); block->steps[A_AXIS] = ABS(da);
block->steps[B_AXIS] = labs(db); block->steps[B_AXIS] = ABS(db);
block->steps[Z_AXIS] = labs(dc); block->steps[Z_AXIS] = ABS(dc);
#else #else
// default non-h-bot planning // default non-h-bot planning
block->steps[A_AXIS] = labs(da); block->steps[A_AXIS] = ABS(da);
block->steps[B_AXIS] = labs(db); block->steps[B_AXIS] = ABS(db);
block->steps[C_AXIS] = labs(dc); block->steps[C_AXIS] = ABS(dc);
#endif #endif
block->steps[E_AXIS] = esteps; 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]; 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) { 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) { else if (!millimeters) {
block->millimeters = SQRT( 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 // Calculate and limit speed in mm/sec for each axis
float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed
LOOP_XYZE(i) { 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 ENABLED(DISTINCT_E_FACTORS)
if (i == E_AXIS) i += extruder; if (i == E_AXIS) i += extruder;
#endif #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), const uint32_t max_x_segment_time = MAX3(xs0, xs1, xs2),
max_y_segment_time = MAX3(ys0, ys1, ys2), 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) { 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);
NOMORE(speed_factor, low_sf); NOMORE(speed_factor, low_sf);
@ -1973,7 +1973,7 @@ void Planner::_buffer_steps(const int32_t (&target)[XYZE]
vmax_junction = MINIMUM_PLANNER_SPEED; vmax_junction = MINIMUM_PLANNER_SPEED;
} }
else { 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. 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 // 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; float safe_speed = block->nominal_speed;
uint8_t limited = 0; uint8_t limited = 0;
LOOP_XYZE(i) { 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 (jerk > maxj) {
if (limited) { if (limited) {
const float mjerk = maxj * block->nominal_speed; 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. // 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. // 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. // Factor to multiply the previous / current nominal velocities to get componentwise limited velocities.
float v_factor = 1; 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. // Calculate jerk depending on whether the axis is coasting in the same direction or reversing.
const float jerk = (v_exit > v_entry) const float jerk = (v_exit > v_entry)
? // coasting axis reversal ? // 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_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]) { if (jerk > max_jerk[axis]) {
v_factor *= max_jerk[axis] / jerk; 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); 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. // 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. // 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 // Initialize planner efficiency flags
// Set flag if block will always reach maximum junction speed regardless of entry/exit speeds. // 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; 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 * We approximate Euclidean distance with the sum of the coordinates
* offset (so-called "norm 1"), which is quicker to compute. * 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 * 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 #endif
if (deploy_stow_condition && unknown_condition) 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) || ENABLED(Z_PROBE_ALLEN_KEY)
#if ENABLED(Z_PROBE_SLED) #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 = const float nz =
#if ENABLED(DELTA) #if ENABLED(DELTA)
// Move below clip height or xy move will be aborted by do_blocking_move_to // 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 #else
current_position[Z_AXIS] current_position[Z_AXIS]
#endif #endif

View file

@ -811,8 +811,8 @@ void Temperature::manage_heater() {
updateTemperaturesFromRawValues(); // also resets the watchdog updateTemperaturesFromRawValues(); // also resets the watchdog
#if ENABLED(HEATER_0_USES_MAX6675) #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] > 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] < MAX(HEATER_0_MINTEMP, MAX6675_TMIN + .01)) min_temp_error(0);
#endif #endif
#if WATCH_HOTENDS || WATCH_THE_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN || HEATER_IDLE_HANDLER #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) #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
// Make sure measured temperatures are close together // 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)); _temp_error(0, PSTR(MSG_REDUNDANCY), PSTR(MSG_ERR_REDUNDANT_TEMP));
#endif #endif
@ -1097,7 +1097,7 @@ void Temperature::updateTemperaturesFromRawValues() {
* a return value of 1. * a return value of 1.
*/ */
int8_t Temperature::widthFil_to_size_ratio() { 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 int(100.0 * filament_width_nominal / filament_width_meas) - 100;
return 0; return 0;
} }

View file

@ -91,7 +91,7 @@ enum ADCSensorState : char {
// get all oversampled sensor readings // get all oversampled sensor readings
#define MIN_ADC_ISR_LOOPS 10 #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 #if HAS_PID_HEATING
#define PID_K2 (1.0-PID_K1) #define PID_K2 (1.0-PID_K1)
@ -440,7 +440,7 @@ class Temperature {
#endif #endif
target_temperature_bed = target_temperature_bed =
#ifdef BED_MAXTEMP #ifdef BED_MAXTEMP
min(celsius, BED_MAXTEMP) MIN(celsius, BED_MAXTEMP)
#else #else
celsius celsius
#endif #endif
@ -463,7 +463,7 @@ class Temperature {
#endif #endif
FORCE_INLINE static bool wait_for_heating(const uint8_t e) { 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;
} }
/** /**