Merge pull request #11178 from ejtagle/misc-fixes

[2.0.x] Use 'float' instead of 'double' maths
This commit is contained in:
Scott Lahteine 2018-07-06 18:53:40 -05:00 committed by GitHub
commit dde009efdf
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
41 changed files with 291 additions and 348 deletions

View file

@ -353,4 +353,7 @@ inline void HAL_adc_init(void) {
#define HAL_SENSITIVE_PINS 0, 1 #define HAL_SENSITIVE_PINS 0, 1
// AVR compatibility
#define strtof strtod
#endif // _HAL_AVR_H_ #endif // _HAL_AVR_H_

View file

@ -297,8 +297,8 @@ char TMC26XStepper::stop(void) {
void TMC26XStepper::setCurrent(unsigned int current) { void TMC26XStepper::setCurrent(unsigned int current) {
unsigned char current_scaling = 0; unsigned char current_scaling = 0;
//calculate the current scaling from the max current setting (in mA) //calculate the current scaling from the max current setting (in mA)
double mASetting = (double)current, float mASetting = (float)current,
resistor_value = (double)this->resistor; resistor_value = (float)this->resistor;
// remove vsense flag // remove vsense flag
this->driver_configuration_register_value &= ~(VSENSE); this->driver_configuration_register_value &= ~(VSENSE);
// Derived from I = (cs + 1) / 32 * (Vsense / Rsense) // Derived from I = (cs + 1) / 32 * (Vsense / Rsense)
@ -340,8 +340,8 @@ void TMC26XStepper::setCurrent(unsigned int current) {
unsigned int TMC26XStepper::getCurrent(void) { unsigned int TMC26XStepper::getCurrent(void) {
// Calculate the current according to the datasheet to be on the safe side. // Calculate the current according to the datasheet to be on the safe side.
// This is not the fastest but the most accurate and illustrative way. // This is not the fastest but the most accurate and illustrative way.
double result = (double)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN), float result = (float)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN),
resistor_value = (double)this->resistor, resistor_value = (float)this->resistor,
voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31; voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31;
result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
return (unsigned int)result; return (unsigned int)result;
@ -739,8 +739,8 @@ unsigned char TMC26XStepper::getCurrentCSReading(void) {
} }
unsigned int TMC26XStepper::getCurrentCurrent(void) { unsigned int TMC26XStepper::getCurrentCurrent(void) {
double result = (double)getCurrentCSReading(), float result = (float)getCurrentCSReading(),
resistor_value = (double)this->resistor, resistor_value = (float)this->resistor,
voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31; voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31;
result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
return (unsigned int)result; return (unsigned int)result;

View file

@ -185,11 +185,6 @@ extern volatile bool wait_for_heatup;
extern bool suspend_auto_report; extern bool suspend_auto_report;
#endif #endif
#if ENABLED(AUTO_BED_LEVELING_UBL)
typedef struct { double A, B, D; } linear_fit;
linear_fit* lsf_linear_fit(double x[], double y[], double z[], const int);
#endif
// Inactivity shutdown timer // Inactivity shutdown timer
extern millis_t max_inactive_time, stepper_inactive_time; extern millis_t max_inactive_time, stepper_inactive_time;

View file

@ -79,15 +79,15 @@
#define CBI32(n,b) (n &= ~_BV32(b)) #define CBI32(n,b) (n &= ~_BV32(b))
// Macros for maths shortcuts // Macros for maths shortcuts
#ifndef M_PI #undef M_PI
#define M_PI 3.14159265358979323846 #define M_PI 3.14159265358979323846f
#endif
#define RADIANS(d) ((d)*M_PI/180.0) #define RADIANS(d) ((d)*float(M_PI)/180.0f)
#define DEGREES(r) ((r)*180.0/M_PI) #define DEGREES(r) ((r)*180.0f/float(M_PI))
#define HYPOT2(x,y) (sq(x)+sq(y)) #define HYPOT2(x,y) (sq(x)+sq(y))
#define CIRCLE_AREA(R) (M_PI * sq(R)) #define CIRCLE_AREA(R) (float(M_PI) * sq(float(R)))
#define CIRCLE_CIRC(R) (2.0 * M_PI * (R)) #define CIRCLE_CIRC(R) (2 * float(M_PI) * float(R))
#define SIGN(a) ((a>0)-(a<0)) #define SIGN(a) ((a>0)-(a<0))
#define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1))) #define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1)))
@ -200,8 +200,8 @@
#define PENDING(NOW,SOON) ((long)(NOW-(SOON))<0) #define PENDING(NOW,SOON) ((long)(NOW-(SOON))<0)
#define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON)) #define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON))
#define MMM_TO_MMS(MM_M) ((MM_M)/60.0) #define MMM_TO_MMS(MM_M) ((MM_M)/60.0f)
#define MMS_TO_MMM(MM_S) ((MM_S)*60.0) #define MMS_TO_MMM(MM_S) ((MM_S)*60.0f)
#define NOOP do{} while(0) #define NOOP do{} while(0)
@ -250,23 +250,24 @@
#define MAX4(a, b, c, d) MAX(MAX3(a, b, c), d) #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 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.000001f)
#define NEAR_ZERO(x) WITHIN(x, -0.000001, 0.000001) #define NEAR_ZERO(x) WITHIN(x, -0.000001f, 0.000001f)
#define NEAR(x,y) NEAR_ZERO((x)-(y)) #define NEAR(x,y) NEAR_ZERO((x)-(y))
#define RECIPROCAL(x) (NEAR_ZERO(x) ? 0.0 : 1.0 / (x)) #define RECIPROCAL(x) (NEAR_ZERO(x) ? 0 : (1 / float(x)))
#define FIXFLOAT(f) (f + (f < 0.0 ? -0.00005 : 0.00005)) #define FIXFLOAT(f) (f + (f < 0 ? -0.00005f : 0.00005f))
// //
// 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) atan2f(y, x)
#define POW(x, y) pow(x, y) #define POW(x, y) powf(x, y)
#define SQRT(x) sqrt(x) #define SQRT(x) sqrtf(x)
#define CEIL(x) ceil(x) #define RSQRT(x) (1 / sqrtf(x))
#define FLOOR(x) floor(x) #define CEIL(x) ceilf(x)
#define LROUND(x) lround(x) #define FLOOR(x) floorf(x)
#define FMOD(x, y) fmod(x, y) #define LROUND(x) lroundf(x)
#define FMOD(x, y) fmodf(x, y)
#define HYPOT(x,y) SQRT(HYPOT2(x,y)) #define HYPOT(x,y) SQRT(HYPOT2(x,y))
#endif //__MACROS_H #endif //__MACROS_H

View file

@ -87,14 +87,14 @@ void safe_delay(millis_t ms);
char* ftostr62rj(const float &x); char* ftostr62rj(const float &x);
// Convert float to rj string with 123 or -12 format // Convert float to rj string with 123 or -12 format
FORCE_INLINE char* ftostr3(const float &x) { return itostr3(int(x + (x < 0 ? -0.5 : 0.5))); } FORCE_INLINE char* ftostr3(const float &x) { return itostr3(int(x + (x < 0 ? -0.5f : 0.5f))); }
#if ENABLED(LCD_DECIMAL_SMALL_XY) #if ENABLED(LCD_DECIMAL_SMALL_XY)
// Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format
char* ftostr4sign(const float &fx); char* ftostr4sign(const float &fx);
#else #else
// Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format
FORCE_INLINE char* ftostr4sign(const float &x) { return itostr4sign(int(x + (x < 0 ? -0.5 : 0.5))); } FORCE_INLINE char* ftostr4sign(const float &x) { return itostr4sign(int(x + (x < 0 ? -0.5f : 0.5f))); }
#endif #endif
#endif // ULTRA_LCD #endif // ULTRA_LCD

View file

@ -181,7 +181,7 @@ void I2CPositionEncoder::update() {
if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) { if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) {
float sumP = 0; float sumP = 0;
LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i]; LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i];
const int32_t errorP = int32_t(sumP * (1.0 / (I2CPE_ERR_PRST_ARRAY_SIZE))); const int32_t errorP = int32_t(sumP * (1.0f / (I2CPE_ERR_PRST_ARRAY_SIZE)));
SERIAL_ECHO(axis_codes[encoderAxis]); SERIAL_ECHO(axis_codes[encoderAxis]);
SERIAL_ECHOPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis]); SERIAL_ECHOPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis]);
SERIAL_ECHOLNPGM("mm; correcting!"); SERIAL_ECHOLNPGM("mm; correcting!");

View file

@ -133,16 +133,12 @@ class I2CPositionEncoder {
nextErrorCountTime = 0, nextErrorCountTime = 0,
lastErrorTime; lastErrorTime;
//double positionMm; //calculate
#if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE)
uint8_t errIdx = 0, errPrstIdx = 0; uint8_t errIdx = 0, errPrstIdx = 0;
int err[I2CPE_ERR_ARRAY_SIZE] = { 0 }, int err[I2CPE_ERR_ARRAY_SIZE] = { 0 },
errPrst[I2CPE_ERR_PRST_ARRAY_SIZE] = { 0 }; errPrst[I2CPE_ERR_PRST_ARRAY_SIZE] = { 0 };
#endif #endif
//float positionMm; //calculate
public: public:
void init(const uint8_t address, const AxisEnum axis); void init(const uint8_t address, const AxisEnum axis);
void reset(); void reset();

View file

@ -72,22 +72,22 @@ public:
} }
static int8_t cell_index_x(const float &x) { static int8_t cell_index_x(const float &x) {
int8_t cx = (x - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST)); int8_t cx = (x - (MESH_MIN_X)) * (1.0f / (MESH_X_DIST));
return constrain(cx, 0, (GRID_MAX_POINTS_X) - 2); return constrain(cx, 0, (GRID_MAX_POINTS_X) - 2);
} }
static int8_t cell_index_y(const float &y) { static int8_t cell_index_y(const float &y) {
int8_t cy = (y - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST)); int8_t cy = (y - (MESH_MIN_Y)) * (1.0f / (MESH_Y_DIST));
return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 2); return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 2);
} }
static int8_t probe_index_x(const float &x) { static int8_t probe_index_x(const float &x) {
int8_t px = (x - (MESH_MIN_X) + 0.5 * (MESH_X_DIST)) * (1.0 / (MESH_X_DIST)); int8_t px = (x - (MESH_MIN_X) + 0.5 * (MESH_X_DIST)) * (1.0f / (MESH_X_DIST));
return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1; return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1;
} }
static int8_t probe_index_y(const float &y) { static int8_t probe_index_y(const float &y) {
int8_t py = (y - (MESH_MIN_Y) + 0.5 * (MESH_Y_DIST)) * (1.0 / (MESH_Y_DIST)); int8_t py = (y - (MESH_MIN_Y) + 0.5 * (MESH_Y_DIST)) * (1.0f / (MESH_Y_DIST));
return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1; return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1;
} }

View file

@ -168,14 +168,14 @@ class unified_bed_leveling {
FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; } FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; }
static int8_t get_cell_index_x(const float &x) { static int8_t get_cell_index_x(const float &x) {
const int8_t cx = (x - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST)); const int8_t cx = (x - (MESH_MIN_X)) * (1.0f / (MESH_X_DIST));
return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1); // -1 is appropriate if we want all movement to the X_MAX return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1); // -1 is appropriate if we want all movement to the X_MAX
} // position. But with this defined this way, it is possible } // position. But with this defined this way, it is possible
// to extrapolate off of this point even further out. Probably // to extrapolate off of this point even further out. Probably
// that is OK because something else should be keeping that from // that is OK because something else should be keeping that from
// happening and should not be worried about at this level. // happening and should not be worried about at this level.
static int8_t get_cell_index_y(const float &y) { static int8_t get_cell_index_y(const float &y) {
const int8_t cy = (y - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST)); const int8_t cy = (y - (MESH_MIN_Y)) * (1.0f / (MESH_Y_DIST));
return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1); // -1 is appropriate if we want all movement to the Y_MAX return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1); // -1 is appropriate if we want all movement to the Y_MAX
} // position. But with this defined this way, it is possible } // position. But with this defined this way, it is possible
// to extrapolate off of this point even further out. Probably // to extrapolate off of this point even further out. Probably
@ -183,12 +183,12 @@ class unified_bed_leveling {
// happening and should not be worried about at this level. // happening and should not be worried about at this level.
static int8_t find_closest_x_index(const float &x) { static int8_t find_closest_x_index(const float &x) {
const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * (1.0 / (MESH_X_DIST)); const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * (1.0f / (MESH_X_DIST));
return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1; return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1;
} }
static int8_t find_closest_y_index(const float &y) { static int8_t find_closest_y_index(const float &y) {
const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * (1.0 / (MESH_Y_DIST)); const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * (1.0f / (MESH_Y_DIST));
return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1; return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1;
} }
@ -238,7 +238,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.0f / (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
@ -272,7 +272,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.0f / (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

View file

@ -874,8 +874,8 @@
serialprintPGM(parser.seen('B') ? PSTR(MSG_UBL_BC_INSERT) : PSTR(MSG_UBL_BC_INSERT2)); serialprintPGM(parser.seen('B') ? PSTR(MSG_UBL_BC_INSERT) : PSTR(MSG_UBL_BC_INSERT2));
const float z_step = 0.01; // existing behavior: 0.01mm per click, occasionally step const float z_step = 0.01; // existing behavior: 0.01mm per click, occasionally step
//const float z_step = 1.0 / planner.axis_steps_per_mm[Z_AXIS]; // approx one step each click //const float z_step = planner.steps_to_mm[Z_AXIS]; // approx one step each click
move_z_with_encoder(z_step); move_z_with_encoder(z_step);
@ -1252,7 +1252,7 @@
// last half of the mesh (when every unprobed mesh point is one index // last half of the mesh (when every unprobed mesh point is one index
// from a probed location). // from a probed location).
d1 = HYPOT(i - k, j - l) + (1.0 / ((millis() % 47) + 13)); d1 = HYPOT(i - k, j - l) + (1.0f / ((millis() % 47) + 13));
if (d1 < d2) { // found a closer distance from invalid mesh point at (i,j) to defined mesh point at (k,l) if (d1 < d2) { // found a closer distance from invalid mesh point at (i,j) to defined mesh point at (k,l)
d2 = d1; // found a closer location with d2 = d1; // found a closer location with

View file

@ -102,7 +102,7 @@
FINAL_MOVE: FINAL_MOVE:
// The distance is always MESH_X_DIST so multiply by the constant reciprocal. // The distance is always MESH_X_DIST so multiply by the constant reciprocal.
const float xratio = (end[X_AXIS] - mesh_index_to_xpos(cell_dest_xi)) * (1.0 / (MESH_X_DIST)); const float xratio = (end[X_AXIS] - mesh_index_to_xpos(cell_dest_xi)) * (1.0f / (MESH_X_DIST));
float z1 = z_values[cell_dest_xi ][cell_dest_yi ] + xratio * float z1 = z_values[cell_dest_xi ][cell_dest_yi ] + xratio *
(z_values[cell_dest_xi + 1][cell_dest_yi ] - z_values[cell_dest_xi][cell_dest_yi ]), (z_values[cell_dest_xi + 1][cell_dest_yi ] - z_values[cell_dest_xi][cell_dest_yi ]),
@ -112,7 +112,7 @@
if (cell_dest_xi >= GRID_MAX_POINTS_X - 1) z1 = z2 = 0.0; if (cell_dest_xi >= GRID_MAX_POINTS_X - 1) z1 = z2 = 0.0;
// X cell-fraction done. Interpolate the two Z offsets with the Y fraction for the final Z offset. // X cell-fraction done. Interpolate the two Z offsets with the Y fraction for the final Z offset.
const float yratio = (end[Y_AXIS] - mesh_index_to_ypos(cell_dest_yi)) * (1.0 / (MESH_Y_DIST)), const float yratio = (end[Y_AXIS] - mesh_index_to_ypos(cell_dest_yi)) * (1.0f / (MESH_Y_DIST)),
z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0; z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0;
// Undefined parts of the Mesh in z_values[][] are NAN. // Undefined parts of the Mesh in z_values[][] are NAN.
@ -440,14 +440,14 @@
#if IS_KINEMATIC #if IS_KINEMATIC
const float seconds = cartesian_xy_mm / feedrate; // seconds to move xy distance at requested rate const float seconds = cartesian_xy_mm / feedrate; // seconds to move xy distance at requested rate
uint16_t segments = lroundf(delta_segments_per_second * seconds), // preferred number of segments for distance @ feedrate uint16_t segments = lroundf(delta_segments_per_second * seconds), // preferred number of segments for distance @ feedrate
seglimit = lroundf(cartesian_xy_mm * (1.0 / (DELTA_SEGMENT_MIN_LENGTH))); // number of segments at minimum segment length seglimit = lroundf(cartesian_xy_mm * (1.0f / (DELTA_SEGMENT_MIN_LENGTH))); // number of segments at minimum segment length
NOMORE(segments, seglimit); // limit to minimum segment length (fewer segments) NOMORE(segments, seglimit); // limit to minimum segment length (fewer segments)
#else #else
uint16_t segments = lroundf(cartesian_xy_mm * (1.0 / (DELTA_SEGMENT_MIN_LENGTH))); // cartesian fixed segment length uint16_t segments = lroundf(cartesian_xy_mm * (1.0f / (DELTA_SEGMENT_MIN_LENGTH))); // cartesian fixed segment length
#endif #endif
NOLESS(segments, 1U); // must have at least one segment NOLESS(segments, 1U); // must have at least one segment
const float inv_segments = 1.0 / segments; // divide once, multiply thereafter const float inv_segments = 1.0f / segments; // divide once, multiply thereafter
#if IS_SCARA // scale the feed rate from mm/s to degrees/s #if IS_SCARA // scale the feed rate from mm/s to degrees/s
scara_feed_factor = cartesian_xy_mm * inv_segments * feedrate; scara_feed_factor = cartesian_xy_mm * inv_segments * feedrate;
@ -500,8 +500,8 @@
// in top of loop and again re-find same adjacent cell and use it, just less efficient // in top of loop and again re-find same adjacent cell and use it, just less efficient
// for mesh inset area. // for mesh inset area.
int8_t cell_xi = (raw[X_AXIS] - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST)), int8_t cell_xi = (raw[X_AXIS] - (MESH_MIN_X)) * (1.0f / (MESH_X_DIST)),
cell_yi = (raw[Y_AXIS] - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST)); cell_yi = (raw[Y_AXIS] - (MESH_MIN_Y)) * (1.0f / (MESH_Y_DIST));
cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1); cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1);
cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1); cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1);
@ -522,15 +522,15 @@
float cx = raw[X_AXIS] - x0, // cell-relative x and y float cx = raw[X_AXIS] - x0, // cell-relative x and y
cy = raw[Y_AXIS] - y0; cy = raw[Y_AXIS] - y0;
const float z_xmy0 = (z_x1y0 - z_x0y0) * (1.0 / (MESH_X_DIST)), // z slope per x along y0 (lower left to lower right) const float z_xmy0 = (z_x1y0 - z_x0y0) * (1.0f / (MESH_X_DIST)), // z slope per x along y0 (lower left to lower right)
z_xmy1 = (z_x1y1 - z_x0y1) * (1.0 / (MESH_X_DIST)); // z slope per x along y1 (upper left to upper right) z_xmy1 = (z_x1y1 - z_x0y1) * (1.0f / (MESH_X_DIST)); // z slope per x along y1 (upper left to upper right)
float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx (changes for each cx in cell) float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx (changes for each cx in cell)
const float z_cxy1 = z_x0y1 + z_xmy1 * cx, // z height along y1 at cx const float z_cxy1 = z_x0y1 + z_xmy1 * cx, // z height along y1 at cx
z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1 z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1
float z_cxym = z_cxyd * (1.0 / (MESH_Y_DIST)); // z slope per y along cx from y0 to y1 (changes for each cx in cell) float z_cxym = z_cxyd * (1.0f / (MESH_Y_DIST)); // z slope per y along cx from y0 to y1 (changes for each cx in cell)
// float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy (do inside the segment loop) // float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy (do inside the segment loop)
@ -539,7 +539,7 @@
// each change by a constant for fixed segment lengths. // each change by a constant for fixed segment lengths.
const float z_sxy0 = z_xmy0 * diff[X_AXIS], // per-segment adjustment to z_cxy0 const float z_sxy0 = z_xmy0 * diff[X_AXIS], // per-segment adjustment to z_cxy0
z_sxym = (z_xmy1 - z_xmy0) * (1.0 / (MESH_Y_DIST)) * diff[X_AXIS]; // per-segment adjustment to z_cxym z_sxym = (z_xmy1 - z_xmy0) * (1.0f / (MESH_Y_DIST)) * diff[X_AXIS]; // per-segment adjustment to z_cxym
for (;;) { // for all segments within this mesh cell for (;;) { // for all segments within this mesh cell

View file

@ -91,8 +91,8 @@ void dac_current_raw(uint8_t channel, uint16_t val) {
mcp4728_simpleCommand(UPDATE); mcp4728_simpleCommand(UPDATE);
} }
static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * (1.0 / (DAC_STEPPER_MAX)); } static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * (1.0f / (DAC_STEPPER_MAX)); }
static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * (1.0 / (DAC_STEPPER_SENSE)); } static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * (1.0f / (DAC_STEPPER_SENSE)); }
uint8_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); } uint8_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); }
void dac_current_set_percents(const uint8_t pct[XYZE]) { void dac_current_set_percents(const uint8_t pct[XYZE]) {

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), 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), DIGIPOT_I2C_MAX_CURRENT)));
} }
void digipot_i2c_init() { void digipot_i2c_init() {

View file

@ -185,7 +185,7 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool
S2 += sq(z_pt[rad]); S2 += sq(z_pt[rad]);
N++; N++;
} }
return round(SQRT(S2 / N) * 1000.0) / 1000.0 + 0.00001; return LROUND(SQRT(S2 / N) * 1000.0) / 1000.0 + 0.00001;
} }
} }
return 0.00001; return 0.00001;
@ -277,8 +277,8 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi
const float z_temp = calibration_probe(cos(a) * r, sin(a) * r, stow_after_each, set_up); const float z_temp = calibration_probe(cos(a) * r, sin(a) * r, stow_after_each, set_up);
if (isnan(z_temp)) return false; if (isnan(z_temp)) return false;
// split probe point to neighbouring calibration points // split probe point to neighbouring calibration points
z_pt[uint8_t(round(rad - interpol + NPP - 1)) % NPP + 1] += z_temp * sq(cos(RADIANS(interpol * 90))); z_pt[uint8_t(LROUND(rad - interpol + NPP - 1)) % NPP + 1] += z_temp * sq(cos(RADIANS(interpol * 90)));
z_pt[uint8_t(round(rad - interpol)) % NPP + 1] += z_temp * sq(sin(RADIANS(interpol * 90))); z_pt[uint8_t(LROUND(rad - interpol)) % NPP + 1] += z_temp * sq(sin(RADIANS(interpol * 90)));
} }
zig_zag = !zig_zag; zig_zag = !zig_zag;
} }
@ -359,7 +359,7 @@ static float auto_tune_h() {
float h_fac = 0.0; float h_fac = 0.0;
h_fac = r_quot / (2.0 / 3.0); h_fac = r_quot / (2.0 / 3.0);
h_fac = 1.0 / h_fac; // (2/3)/CR h_fac = 1.0f / h_fac; // (2/3)/CR
return h_fac; return h_fac;
} }
@ -680,9 +680,9 @@ void GcodeSuite::G33() {
char mess[21]; char mess[21];
strcpy_P(mess, PSTR("Calibration sd:")); strcpy_P(mess, PSTR("Calibration sd:"));
if (zero_std_dev_min < 1) if (zero_std_dev_min < 1)
sprintf_P(&mess[15], PSTR("0.%03i"), (int)round(zero_std_dev_min * 1000.0)); sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev_min * 1000.0));
else else
sprintf_P(&mess[15], PSTR("%03i.x"), (int)round(zero_std_dev_min)); sprintf_P(&mess[15], PSTR("%03i.x"), (int)LROUND(zero_std_dev_min));
lcd_setstatus(mess); lcd_setstatus(mess);
print_calibration_settings(_endstop_results, _angle_results); print_calibration_settings(_endstop_results, _angle_results);
serialprintPGM(save_message); serialprintPGM(save_message);
@ -716,9 +716,9 @@ void GcodeSuite::G33() {
strcpy_P(mess, enddryrun); strcpy_P(mess, enddryrun);
strcpy_P(&mess[11], PSTR(" sd:")); strcpy_P(&mess[11], PSTR(" sd:"));
if (zero_std_dev < 1) if (zero_std_dev < 1)
sprintf_P(&mess[15], PSTR("0.%03i"), (int)round(zero_std_dev * 1000.0)); sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev * 1000.0));
else else
sprintf_P(&mess[15], PSTR("%03i.x"), (int)round(zero_std_dev)); sprintf_P(&mess[15], PSTR("%03i.x"), (int)LROUND(zero_std_dev));
lcd_setstatus(mess); lcd_setstatus(mess);
} }
ac_home(); ac_home();

View file

@ -111,7 +111,7 @@ void GcodeSuite::M48() {
setup_for_endstop_or_probe_move(); setup_for_endstop_or_probe_move();
double mean = 0.0, sigma = 0.0, min = 99999.9, max = -99999.9, sample_set[n_samples]; float mean = 0.0, sigma = 0.0, min = 99999.9, max = -99999.9, sample_set[n_samples];
// Move to the first point, deploy, and probe // Move to the first point, deploy, and probe
const float t = probe_pt(X_probe_location, Y_probe_location, raise_after, verbose_level); const float t = probe_pt(X_probe_location, Y_probe_location, raise_after, verbose_level);
@ -142,7 +142,7 @@ void GcodeSuite::M48() {
} }
for (uint8_t l = 0; l < n_legs - 1; l++) { for (uint8_t l = 0; l < n_legs - 1; l++) {
double delta_angle; float delta_angle;
if (schizoid_flag) if (schizoid_flag)
// The points of a 5 point star are 72 degrees apart. We need to // The points of a 5 point star are 72 degrees apart. We need to
@ -199,7 +199,7 @@ void GcodeSuite::M48() {
/** /**
* Get the current mean for the data points we have so far * Get the current mean for the data points we have so far
*/ */
double sum = 0.0; float sum = 0.0;
for (uint8_t j = 0; j <= n; j++) sum += sample_set[j]; for (uint8_t j = 0; j <= n; j++) sum += sample_set[j];
mean = sum / (n + 1); mean = sum / (n + 1);

View file

@ -40,7 +40,7 @@
// setting any extruder filament size disables volumetric on the assumption that // setting any extruder filament size disables volumetric on the assumption that
// slicers either generate in extruder values as cubic mm or as as filament feeds // slicers either generate in extruder values as cubic mm or as as filament feeds
// for all extruders // for all extruders
if ( (parser.volumetric_enabled = (parser.value_linear_units() != 0.0)) ) if ( (parser.volumetric_enabled = (parser.value_linear_units() != 0)) )
planner.set_filament_size(target_extruder, parser.value_linear_units()); planner.set_filament_size(target_extruder, parser.value_linear_units());
} }
planner.calculate_volumetric_multipliers(); planner.calculate_volumetric_multipliers();
@ -134,7 +134,7 @@ void GcodeSuite::M205() {
#if ENABLED(JUNCTION_DEVIATION) #if ENABLED(JUNCTION_DEVIATION)
if (parser.seen('J')) { if (parser.seen('J')) {
const float junc_dev = parser.value_linear_units(); const float junc_dev = parser.value_linear_units();
if (WITHIN(junc_dev, 0.01, 0.3)) { if (WITHIN(junc_dev, 0.01f, 0.3f)) {
planner.junction_deviation_mm = junc_dev; planner.junction_deviation_mm = junc_dev;
planner.recalculate_max_e_jerk(); planner.recalculate_max_e_jerk();
} }
@ -149,7 +149,7 @@ void GcodeSuite::M205() {
if (parser.seen('Z')) { if (parser.seen('Z')) {
planner.max_jerk[Z_AXIS] = parser.value_linear_units(); planner.max_jerk[Z_AXIS] = parser.value_linear_units();
#if HAS_MESH #if HAS_MESH
if (planner.max_jerk[Z_AXIS] <= 0.1) if (planner.max_jerk[Z_AXIS] <= 0.1f)
SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses.");
#endif #endif
} }

View file

@ -37,7 +37,7 @@ void GcodeSuite::M92() {
if (parser.seen(axis_codes[i])) { if (parser.seen(axis_codes[i])) {
if (i == E_AXIS) { if (i == E_AXIS) {
const float value = parser.value_per_axis_unit((AxisEnum)(E_AXIS + TARGET_EXTRUDER)); const float value = parser.value_per_axis_unit((AxisEnum)(E_AXIS + TARGET_EXTRUDER));
if (value < 20.0) { if (value < 20) {
float factor = planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] / value; // increase e constants if M92 E14 is given for netfab. float factor = planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] / value; // increase e constants if M92 E14 is given for netfab.
#if DISABLED(JUNCTION_DEVIATION) #if DISABLED(JUNCTION_DEVIATION)
planner.max_jerk[E_AXIS] *= factor; planner.max_jerk[E_AXIS] *= factor;

View file

@ -107,12 +107,12 @@ void GcodeSuite::M3_M4(bool is_M3) {
delay_for_power_down(); delay_for_power_down();
} }
else { else {
int16_t ocr_val = (spindle_laser_power - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE)); // convert RPM to PWM duty cycle int16_t ocr_val = (spindle_laser_power - (SPEED_POWER_INTERCEPT)) * (1.0f / (SPEED_POWER_SLOPE)); // convert RPM to PWM duty cycle
NOMORE(ocr_val, 255); // limit to max the Atmel PWM will support NOMORE(ocr_val, 255); // limit to max the Atmel PWM will support
if (spindle_laser_power <= SPEED_POWER_MIN) if (spindle_laser_power <= SPEED_POWER_MIN)
ocr_val = (SPEED_POWER_MIN - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE)); // minimum setting ocr_val = (SPEED_POWER_MIN - (SPEED_POWER_INTERCEPT)) * (1.0f / (SPEED_POWER_SLOPE)); // minimum setting
if (spindle_laser_power >= SPEED_POWER_MAX) if (spindle_laser_power >= SPEED_POWER_MAX)
ocr_val = (SPEED_POWER_MAX - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE)); // limit to max RPM ocr_val = (SPEED_POWER_MAX - (SPEED_POWER_INTERCEPT)) * (1.0f / (SPEED_POWER_SLOPE)); // limit to max RPM
if (SPINDLE_LASER_PWM_INVERT) ocr_val = 255 - ocr_val; if (SPINDLE_LASER_PWM_INVERT) ocr_val = 255 - ocr_val;
WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low) WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
analogWrite(SPINDLE_LASER_PWM_PIN, ocr_val & 0xFF); // only write low byte analogWrite(SPINDLE_LASER_PWM_PIN, ocr_val & 0xFF); // only write low byte

View file

@ -103,7 +103,7 @@ void GcodeSuite::get_destination_from_command() {
destination[i] = current_position[i]; destination[i] = current_position[i];
} }
if (parser.linearval('F') > 0.0) if (parser.linearval('F') > 0)
feedrate_mm_s = MMM_TO_MMS(parser.value_feedrate()); feedrate_mm_s = MMM_TO_MMS(parser.value_feedrate());
#if ENABLED(PRINTCOUNTER) #if ENABLED(PRINTCOUNTER)

View file

@ -92,7 +92,7 @@ void plan_arc(
const float flat_mm = radius * angular_travel, const float flat_mm = radius * angular_travel,
mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(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.001f) return;
uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT)); uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT));
if (segments == 0) segments = 1; if (segments == 0) segments = 1;
@ -129,7 +129,7 @@ void plan_arc(
linear_per_segment = linear_travel / segments, linear_per_segment = linear_travel / segments,
extruder_per_segment = extruder_travel / segments, extruder_per_segment = extruder_travel / segments,
sin_T = theta_per_segment, sin_T = theta_per_segment,
cos_T = 1 - 0.5 * sq(theta_per_segment); // Small angle approximation cos_T = 1 - 0.5f * sq(theta_per_segment); // Small angle approximation
// Initialize the linear axis // Initialize the linear axis
raw[l_axis] = current_position[l_axis]; raw[l_axis] = current_position[l_axis];
@ -143,7 +143,7 @@ void plan_arc(
#if HAS_FEEDRATE_SCALING #if HAS_FEEDRATE_SCALING
// SCARA needs to scale the feed rate from mm/s to degrees/s // SCARA needs to scale the feed rate from mm/s to degrees/s
const float inv_segment_length = 1.0 / (MM_PER_ARC_SEGMENT), const float inv_segment_length = 1.0f / float(MM_PER_ARC_SEGMENT),
inverse_secs = inv_segment_length * fr_mm_s; inverse_secs = inv_segment_length * fr_mm_s;
float oldA = planner.position_float[A_AXIS], float oldA = planner.position_float[A_AXIS],
oldB = planner.position_float[B_AXIS] oldB = planner.position_float[B_AXIS]
@ -289,19 +289,20 @@ void GcodeSuite::G2_G3(const bool clockwise) {
relative_mode = relative_mode_backup; relative_mode = relative_mode_backup;
#endif #endif
float arc_offset[2] = { 0.0, 0.0 }; float arc_offset[2] = { 0, 0 };
if (parser.seenval('R')) { if (parser.seenval('R')) {
const float r = parser.value_linear_units(), const float r = parser.value_linear_units(),
p1 = current_position[X_AXIS], q1 = current_position[Y_AXIS], p1 = current_position[X_AXIS], q1 = current_position[Y_AXIS],
p2 = destination[X_AXIS], q2 = destination[Y_AXIS]; p2 = destination[X_AXIS], q2 = destination[Y_AXIS];
if (r && (p2 != p1 || q2 != q1)) { if (r && (p2 != p1 || q2 != q1)) {
const float e = clockwise ^ (r < 0) ? -1 : 1, // clockwise -1/1, counterclockwise 1/-1 const float e = clockwise ^ (r < 0) ? -1 : 1, // clockwise -1/1, counterclockwise 1/-1
dx = p2 - p1, dy = q2 - q1, // X and Y differences dx = p2 - p1, dy = q2 - q1, // X and Y differences
d = HYPOT(dx, dy), // Linear distance between the points d = HYPOT(dx, dy), // Linear distance between the points
h = SQRT(sq(r) - sq(d * 0.5)), // Distance to the arc pivot-point dinv = 1/d, // Inverse of d
mx = (p1 + p2) * 0.5, my = (q1 + q2) * 0.5, // Point between the two points h = SQRT(sq(r) - sq(d * 0.5f)), // Distance to the arc pivot-point
sx = -dy / d, sy = dx / d, // Slope of the perpendicular bisector mx = (p1 + p2) * 0.5f, my = (q1 + q2) * 0.5f,// Point between the two points
cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc sx = -dy * dinv, sy = dx * dinv, // Slope of the perpendicular bisector
cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc
arc_offset[0] = cx - p1; arc_offset[0] = cx - p1;
arc_offset[1] = cy - q1; arc_offset[1] = cy - q1;
} }

View file

@ -186,15 +186,15 @@ public:
if (c == '\0' || c == ' ') break; if (c == '\0' || c == ' ') break;
if (c == 'E' || c == 'e') { if (c == 'E' || c == 'e') {
*e = '\0'; *e = '\0';
const float ret = strtod(value_ptr, NULL); const float ret = strtof(value_ptr, NULL);
*e = c; *e = c;
return ret; return ret;
} }
++e; ++e;
} }
return strtod(value_ptr, NULL); return strtof(value_ptr, NULL);
} }
return 0.0; return 0;
} }
// Code value as a long or ulong // Code value as a long or ulong
@ -203,7 +203,7 @@ public:
// Code value for use as time // Code value for use as time
FORCE_INLINE static millis_t value_millis() { return value_ulong(); } FORCE_INLINE static millis_t value_millis() { return value_ulong(); }
FORCE_INLINE static millis_t value_millis_from_seconds() { return value_float() * 1000UL; } FORCE_INLINE static millis_t value_millis_from_seconds() { return (millis_t)(value_float() * 1000); }
// Reduce to fewer bits // Reduce to fewer bits
FORCE_INLINE static int16_t value_int() { return (int16_t)value_long(); } FORCE_INLINE static int16_t value_int() { return (int16_t)value_long(); }
@ -220,14 +220,14 @@ public:
inline static void set_input_linear_units(const LinearUnit units) { inline static void set_input_linear_units(const LinearUnit units) {
switch (units) { switch (units) {
case LINEARUNIT_INCH: case LINEARUNIT_INCH:
linear_unit_factor = 25.4; linear_unit_factor = 25.4f;
break; break;
case LINEARUNIT_MM: case LINEARUNIT_MM:
default: default:
linear_unit_factor = 1.0; linear_unit_factor = 1;
break; break;
} }
volumetric_unit_factor = POW(linear_unit_factor, 3.0); volumetric_unit_factor = POW(linear_unit_factor, 3);
} }
inline static float axis_unit_factor(const AxisEnum axis) { inline static float axis_unit_factor(const AxisEnum axis) {
@ -261,9 +261,9 @@ public:
inline static float to_temp_units(const float &f) { inline static float to_temp_units(const float &f) {
switch (input_temp_units) { switch (input_temp_units) {
case TEMPUNIT_F: case TEMPUNIT_F:
return f * 0.5555555556 + 32.0; return f * 0.5555555556f + 32;
case TEMPUNIT_K: case TEMPUNIT_K:
return f + 273.15; return f + 273.15f;
case TEMPUNIT_C: case TEMPUNIT_C:
default: default:
return f; return f;
@ -276,9 +276,9 @@ public:
const float f = value_float(); const float f = value_float();
switch (input_temp_units) { switch (input_temp_units) {
case TEMPUNIT_F: case TEMPUNIT_F:
return (f - 32.0) * 0.5555555556; return (f - 32) * 0.5555555556f;
case TEMPUNIT_K: case TEMPUNIT_K:
return f - 273.15; return f - 273.15f;
case TEMPUNIT_C: case TEMPUNIT_C:
default: default:
return f; return f;
@ -288,7 +288,7 @@ public:
inline static float value_celsius_diff() { inline static float value_celsius_diff() {
switch (input_temp_units) { switch (input_temp_units) {
case TEMPUNIT_F: case TEMPUNIT_F:
return value_float() * 0.5555555556; return value_float() * 0.5555555556f;
case TEMPUNIT_C: case TEMPUNIT_C:
case TEMPUNIT_K: case TEMPUNIT_K:
default: default:
@ -315,8 +315,8 @@ public:
FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; }
FORCE_INLINE static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } FORCE_INLINE static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; }
FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; }
FORCE_INLINE static float linearval(const char c, const float dval=0.0) { return seenval(c) ? value_linear_units() : dval; } FORCE_INLINE static float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; }
FORCE_INLINE static float celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius() : dval; } FORCE_INLINE static float celsiusval(const char c, const float dval=0){ return seenval(c) ? value_celsius() : dval; }
}; };

View file

@ -225,7 +225,7 @@ void GcodeSuite::M109() {
// break after MIN_COOLING_SLOPE_TIME seconds // break after MIN_COOLING_SLOPE_TIME seconds
// if the temperature did not drop at least MIN_COOLING_SLOPE_DEG // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG
if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) { if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
if (old_temp - temp < MIN_COOLING_SLOPE_DEG) break; if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG)) break;
next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME; next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME;
old_temp = temp; old_temp = temp;
} }

View file

@ -82,7 +82,7 @@ void GcodeSuite::M190() {
#define TEMP_BED_CONDITIONS (wants_to_cool ? thermalManager.isCoolingBed() : thermalManager.isHeatingBed()) #define TEMP_BED_CONDITIONS (wants_to_cool ? thermalManager.isCoolingBed() : thermalManager.isHeatingBed())
#endif #endif
float target_temp = -1.0, old_temp = 9999.0; float target_temp = -1, old_temp = 9999;
bool wants_to_cool = false; bool wants_to_cool = false;
wait_for_heatup = true; wait_for_heatup = true;
millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; millis_t now, next_temp_ms = 0, next_cool_check_ms = 0;
@ -163,7 +163,7 @@ void GcodeSuite::M190() {
// Break after MIN_COOLING_SLOPE_TIME_BED seconds // Break after MIN_COOLING_SLOPE_TIME_BED seconds
// if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_BED // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_BED
if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) { if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
if (old_temp - temp < MIN_COOLING_SLOPE_DEG_BED) break; if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG_BED)) break;
next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME_BED; next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME_BED;
old_temp = temp; old_temp = temp;
} }

View file

@ -1353,25 +1353,6 @@
#endif #endif
#endif #endif
// Use float instead of double. Needs profiling.
#if defined(ARDUINO_ARCH_SAM) && ENABLED(DELTA_FAST_SQRT)
#undef ATAN2
#undef FABS
#undef POW
#undef SQRT
#undef CEIL
#undef FLOOR
#undef LROUND
#undef FMOD
#define ATAN2(y, x) atan2f(y, x)
#define POW(x, y) powf(x, y)
#define SQRT(x) sqrtf(x)
#define CEIL(x) ceilf(x)
#define FLOOR(x) floorf(x)
#define LROUND(x) lroundf(x)
#define FMOD(x, y) fmodf(x, y)
#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

@ -72,7 +72,7 @@ FORCE_INLINE void _draw_heater_status(const uint8_t x, const int8_t heater, cons
} }
if (PAGE_CONTAINS(21, 28)) { if (PAGE_CONTAINS(21, 28)) {
_draw_centered_temp(0.5 + ( _draw_centered_temp(0.5f + (
#if HAS_HEATED_BED #if HAS_HEATED_BED
isBed ? thermalManager.degBed() : isBed ? thermalManager.degBed() :
#endif #endif

View file

@ -479,7 +479,7 @@ uint16_t max_display_update_time = 0;
#if IS_KINEMATIC #if IS_KINEMATIC
bool processing_manual_move = false; bool processing_manual_move = false;
float manual_move_offset = 0.0; float manual_move_offset = 0;
#else #else
constexpr bool processing_manual_move = false; constexpr bool processing_manual_move = false;
#endif #endif
@ -1285,13 +1285,13 @@ void lcd_quick_feedback(const bool clear_buttons) {
ubl_encoderPosition = (ubl.encoder_diff > 0) ? 1 : -1; ubl_encoderPosition = (ubl.encoder_diff > 0) ? 1 : -1;
ubl.encoder_diff = 0; ubl.encoder_diff = 0;
mesh_edit_accumulator += float(ubl_encoderPosition) * 0.005 / 2.0; mesh_edit_accumulator += float(ubl_encoderPosition) * 0.005f * 0.5f;
mesh_edit_value = mesh_edit_accumulator; mesh_edit_value = mesh_edit_accumulator;
encoderPosition = 0; encoderPosition = 0;
lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT;
const int32_t rounded = (int32_t)(mesh_edit_value * 1000.0); const int32_t rounded = (int32_t)(mesh_edit_value * 1000);
mesh_edit_value = float(rounded - (rounded % 5L)) / 1000.0; mesh_edit_value = float(rounded - (rounded % 5L)) / 1000;
} }
if (lcdDrawUpdate) { if (lcdDrawUpdate) {
@ -1419,7 +1419,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
// Leveling Fade Height // Leveling Fade Height
// //
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(SLIM_LCD_MENUS) #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(SLIM_LCD_MENUS)
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
#endif #endif
// //
@ -1978,7 +1978,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
// //
if (encoderPosition) { if (encoderPosition) {
const float z = current_position[Z_AXIS] + float((int32_t)encoderPosition) * (MBL_Z_STEP); const float z = current_position[Z_AXIS] + float((int32_t)encoderPosition) * (MBL_Z_STEP);
line_to_z(constrain(z, -(LCD_PROBE_Z_RANGE) * 0.5, (LCD_PROBE_Z_RANGE) * 0.5)); line_to_z(constrain(z, -(LCD_PROBE_Z_RANGE) * 0.5f, (LCD_PROBE_Z_RANGE) * 0.5f));
lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT;
encoderPosition = 0; encoderPosition = 0;
} }
@ -1988,7 +1988,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
// //
if (lcdDrawUpdate) { if (lcdDrawUpdate) {
const float v = current_position[Z_AXIS]; const float v = current_position[Z_AXIS];
lcd_implementation_drawedit(PSTR(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001 : 0.0001), '+')); lcd_implementation_drawedit(PSTR(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001f : 0.0001f), '+'));
} }
} }
@ -2571,7 +2571,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu);
MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W")); MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W"));
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
#endif #endif
END_MENU(); END_MENU();
} }
@ -2627,7 +2627,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
// Z Fade Height // Z Fade Height
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
#endif #endif
// //
@ -2713,7 +2713,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &new_level_state, _lcd_toggle_bed_leveling); MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &new_level_state, _lcd_toggle_bed_leveling);
} }
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
#endif #endif
#endif #endif
@ -2877,15 +2877,15 @@ void lcd_quick_feedback(const bool clear_buttons) {
void lcd_delta_settings() { void lcd_delta_settings() {
START_MENU(); START_MENU();
MENU_BACK(MSG_DELTA_CALIBRATE); MENU_BACK(MSG_DELTA_CALIBRATE);
MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_HEIGHT, &delta_height, delta_height - 10.0, delta_height + 10.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_HEIGHT, &delta_height, delta_height - 10, delta_height + 10, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float43, "Ex", &delta_endstop_adj[A_AXIS], -5.0, 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float43, "Ex", &delta_endstop_adj[A_AXIS], -5, 5, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float43, "Ey", &delta_endstop_adj[B_AXIS], -5.0, 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float43, "Ey", &delta_endstop_adj[B_AXIS], -5, 5, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float43, "Ez", &delta_endstop_adj[C_AXIS], -5.0, 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float43, "Ez", &delta_endstop_adj[C_AXIS], -5, 5, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_RADIUS, &delta_radius, delta_radius - 5.0, delta_radius + 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_RADIUS, &delta_radius, delta_radius - 5, delta_radius + 5, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5.0, 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5, 5, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5.0, 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5, 5, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float43, "Tz", &delta_tower_angle_trim[C_AXIS], -5.0, 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float43, "Tz", &delta_tower_angle_trim[C_AXIS], -5, 5, _recalc_delta_settings);
MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_DIAG_ROD, &delta_diagonal_rod, delta_diagonal_rod - 5.0, delta_diagonal_rod + 5.0, _recalc_delta_settings); MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_DIAG_ROD, &delta_diagonal_rod, delta_diagonal_rod - 5, delta_diagonal_rod + 5, _recalc_delta_settings);
END_MENU(); END_MENU();
} }
@ -2981,7 +2981,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
#endif #endif
manual_move_e_index = eindex >= 0 ? eindex : active_extruder; manual_move_e_index = eindex >= 0 ? eindex : active_extruder;
#endif #endif
manual_move_start_time = millis() + (move_menu_scale < 0.99 ? 0UL : 250UL); // delay for bigger moves manual_move_start_time = millis() + (move_menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves
manual_move_axis = (int8_t)axis; manual_move_axis = (int8_t)axis;
} }
@ -3065,7 +3065,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
+ manual_move_offset + manual_move_offset
#endif #endif
, axis); , axis);
lcd_implementation_drawedit(name, move_menu_scale >= 0.1 ? ftostr41sign(pos) : ftostr43sign(pos)); lcd_implementation_drawedit(name, move_menu_scale >= 0.1f ? ftostr41sign(pos) : ftostr43sign(pos));
} }
} }
void lcd_move_x() { _lcd_move_xyz(PSTR(MSG_MOVE_X), X_AXIS); } void lcd_move_x() { _lcd_move_xyz(PSTR(MSG_MOVE_X), X_AXIS); }
@ -3150,9 +3150,9 @@ void lcd_quick_feedback(const bool clear_buttons) {
move_menu_scale = scale; move_menu_scale = scale;
lcd_goto_screen(_manual_move_func_ptr); lcd_goto_screen(_manual_move_func_ptr);
} }
void lcd_move_menu_10mm() { _goto_manual_move(10.0); } void lcd_move_menu_10mm() { _goto_manual_move(10); }
void lcd_move_menu_1mm() { _goto_manual_move( 1.0); } void lcd_move_menu_1mm() { _goto_manual_move( 1); }
void lcd_move_menu_01mm() { _goto_manual_move( 0.1); } void lcd_move_menu_01mm() { _goto_manual_move( 0.1f); }
void _lcd_move_distance_menu(const AxisEnum axis, const screenFunc_t func) { void _lcd_move_distance_menu(const AxisEnum axis, const screenFunc_t func) {
_manual_move_func_ptr = func; _manual_move_func_ptr = func;
@ -3527,9 +3527,9 @@ void lcd_quick_feedback(const bool clear_buttons) {
// //
#if ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND #if ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND
MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &planner.autotemp_enabled); MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &planner.autotemp_enabled);
MENU_ITEM_EDIT(float3, MSG_MIN, &planner.autotemp_min, 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(float3, MSG_MIN, &planner.autotemp_min, 0, float(HEATER_0_MAXTEMP) - 15);
MENU_ITEM_EDIT(float3, MSG_MAX, &planner.autotemp_max, 0, HEATER_0_MAXTEMP - 15); MENU_ITEM_EDIT(float3, MSG_MAX, &planner.autotemp_max, 0, float(HEATER_0_MAXTEMP) - 15);
MENU_ITEM_EDIT(float52, MSG_FACTOR, &planner.autotemp_factor, 0.0, 1.0); MENU_ITEM_EDIT(float52, MSG_FACTOR, &planner.autotemp_factor, 0, 1);
#endif #endif
// //
@ -3546,7 +3546,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
raw_Ki = unscalePID_i(PID_PARAM(Ki, eindex)); \ raw_Ki = unscalePID_i(PID_PARAM(Ki, eindex)); \
raw_Kd = unscalePID_d(PID_PARAM(Kd, eindex)); \ raw_Kd = unscalePID_d(PID_PARAM(Kd, eindex)); \
MENU_ITEM_EDIT(float52sign, MSG_PID_P ELABEL, &PID_PARAM(Kp, eindex), 1, 9990); \ MENU_ITEM_EDIT(float52sign, MSG_PID_P ELABEL, &PID_PARAM(Kp, eindex), 1, 9990); \
MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_I ELABEL, &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E ## eindex); \ MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_I ELABEL, &raw_Ki, 0.01f, 9990, copy_and_scalePID_i_E ## eindex); \
MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_D ELABEL, &raw_Kd, 1, 9990, copy_and_scalePID_d_E ## eindex) MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_D ELABEL, &raw_Kd, 1, 9990, copy_and_scalePID_d_E ## eindex)
#if ENABLED(PID_EXTRUSION_SCALING) #if ENABLED(PID_EXTRUSION_SCALING)
@ -3668,7 +3668,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
if (e == active_extruder) if (e == active_extruder)
_planner_refresh_positioning(); _planner_refresh_positioning();
else else
planner.steps_to_mm[E_AXIS + e] = 1.0 / planner.axis_steps_per_mm[E_AXIS + e]; planner.steps_to_mm[E_AXIS + e] = 1.0f / planner.axis_steps_per_mm[E_AXIS + e];
} }
void _planner_refresh_e0_positioning() { _planner_refresh_e_positioning(0); } void _planner_refresh_e0_positioning() { _planner_refresh_e_positioning(0); }
void _planner_refresh_e1_positioning() { _planner_refresh_e_positioning(1); } void _planner_refresh_e1_positioning() { _planner_refresh_e_positioning(1); }
@ -3764,14 +3764,14 @@ void lcd_quick_feedback(const bool clear_buttons) {
MENU_BACK(MSG_MOTION); MENU_BACK(MSG_MOTION);
#if ENABLED(JUNCTION_DEVIATION) #if ENABLED(JUNCTION_DEVIATION)
MENU_ITEM_EDIT_CALLBACK(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.01, 0.3, planner.recalculate_max_e_jerk); MENU_ITEM_EDIT_CALLBACK(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.01f, 0.3f, planner.recalculate_max_e_jerk);
#else #else
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VA_JERK, &planner.max_jerk[A_AXIS], 1, 990); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VA_JERK, &planner.max_jerk[A_AXIS], 1, 990);
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VB_JERK, &planner.max_jerk[B_AXIS], 1, 990); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VB_JERK, &planner.max_jerk[B_AXIS], 1, 990);
#if ENABLED(DELTA) #if ENABLED(DELTA)
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 1, 990); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 1, 990);
#else #else
MENU_MULTIPLIER_ITEM_EDIT(float52sign, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 0.1, 990); MENU_MULTIPLIER_ITEM_EDIT(float52sign, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 0.1f, 990);
#endif #endif
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_jerk[E_AXIS], 1, 990); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_jerk[E_AXIS], 1, 990);
#endif #endif
@ -3869,17 +3869,17 @@ void lcd_quick_feedback(const bool clear_buttons) {
if (parser.volumetric_enabled) { if (parser.volumetric_enabled) {
#if EXTRUDERS == 1 #if EXTRUDERS == 1
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[0], 1.5, 3.25, planner.calculate_volumetric_multipliers); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[0], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
#else // EXTRUDERS > 1 #else // EXTRUDERS > 1
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[active_extruder], 1.5, 3.25, planner.calculate_volumetric_multipliers); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[active_extruder], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E1, &planner.filament_size[0], 1.5, 3.25, planner.calculate_volumetric_multipliers); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E1, &planner.filament_size[0], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E2, &planner.filament_size[1], 1.5, 3.25, planner.calculate_volumetric_multipliers); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E2, &planner.filament_size[1], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
#if EXTRUDERS > 2 #if EXTRUDERS > 2
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E3, &planner.filament_size[2], 1.5, 3.25, planner.calculate_volumetric_multipliers); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E3, &planner.filament_size[2], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
#if EXTRUDERS > 3 #if EXTRUDERS > 3
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E4, &planner.filament_size[3], 1.5, 3.25, planner.calculate_volumetric_multipliers); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E4, &planner.filament_size[3], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
#if EXTRUDERS > 4 #if EXTRUDERS > 4
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E5, &planner.filament_size[4], 1.5, 3.25, planner.calculate_volumetric_multipliers); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E5, &planner.filament_size[4], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
#endif // EXTRUDERS > 4 #endif // EXTRUDERS > 4
#endif // EXTRUDERS > 3 #endif // EXTRUDERS > 3
#endif // EXTRUDERS > 2 #endif // EXTRUDERS > 2
@ -3892,39 +3892,39 @@ void lcd_quick_feedback(const bool clear_buttons) {
#if ENABLED(PREVENT_LENGTHY_EXTRUDE) #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
EXTRUDE_MAXLENGTH EXTRUDE_MAXLENGTH
#else #else
999.0f 999
#endif #endif
; ;
#if EXTRUDERS == 1 #if EXTRUDERS == 1
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[0], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[0], 0, extrude_maxlength);
#else // EXTRUDERS > 1 #else // EXTRUDERS > 1
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[active_extruder], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[active_extruder], 0, extrude_maxlength);
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E1, &filament_change_unload_length[0], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E1, &filament_change_unload_length[0], 0, extrude_maxlength);
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E2, &filament_change_unload_length[1], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E2, &filament_change_unload_length[1], 0, extrude_maxlength);
#if EXTRUDERS > 2 #if EXTRUDERS > 2
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E3, &filament_change_unload_length[2], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E3, &filament_change_unload_length[2], 0, extrude_maxlength);
#if EXTRUDERS > 3 #if EXTRUDERS > 3
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E4, &filament_change_unload_length[3], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E4, &filament_change_unload_length[3], 0, extrude_maxlength);
#if EXTRUDERS > 4 #if EXTRUDERS > 4
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E5, &filament_change_unload_length[4], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E5, &filament_change_unload_length[4], 0, extrude_maxlength);
#endif // EXTRUDERS > 4 #endif // EXTRUDERS > 4
#endif // EXTRUDERS > 3 #endif // EXTRUDERS > 3
#endif // EXTRUDERS > 2 #endif // EXTRUDERS > 2
#endif // EXTRUDERS > 1 #endif // EXTRUDERS > 1
#if EXTRUDERS == 1 #if EXTRUDERS == 1
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[0], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[0], 0, extrude_maxlength);
#else // EXTRUDERS > 1 #else // EXTRUDERS > 1
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[active_extruder], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[active_extruder], 0, extrude_maxlength);
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E1, &filament_change_load_length[0], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E1, &filament_change_load_length[0], 0, extrude_maxlength);
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E2, &filament_change_load_length[1], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E2, &filament_change_load_length[1], 0, extrude_maxlength);
#if EXTRUDERS > 2 #if EXTRUDERS > 2
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E3, &filament_change_load_length[2], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E3, &filament_change_load_length[2], 0, extrude_maxlength);
#if EXTRUDERS > 3 #if EXTRUDERS > 3
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E4, &filament_change_load_length[3], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E4, &filament_change_load_length[3], 0, extrude_maxlength);
#if EXTRUDERS > 4 #if EXTRUDERS > 4
MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E5, &filament_change_load_length[4], 0.0, extrude_maxlength); MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E5, &filament_change_load_length[4], 0, extrude_maxlength);
#endif // EXTRUDERS > 4 #endif // EXTRUDERS > 4
#endif // EXTRUDERS > 3 #endif // EXTRUDERS > 3
#endif // EXTRUDERS > 2 #endif // EXTRUDERS > 2
@ -4824,9 +4824,9 @@ void lcd_quick_feedback(const bool clear_buttons) {
if ((int32_t)encoderPosition < 0) encoderPosition = 0; \ if ((int32_t)encoderPosition < 0) encoderPosition = 0; \
if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \ if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \
if (lcdDrawUpdate) \ if (lcdDrawUpdate) \
lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale))); \ lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) * (1.0f / _scale))); \
if (lcd_clicked || (liveEdit && lcdDrawUpdate)) { \ if (lcd_clicked || (liveEdit && lcdDrawUpdate)) { \
_type value = ((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale); \ _type value = ((_type)((int32_t)encoderPosition + minEditValue)) * (1.0f / _scale); \
if (editValue != NULL) *((_type*)editValue) = value; \ if (editValue != NULL) *((_type*)editValue) = value; \
if (callbackFunc && (liveEdit || lcd_clicked)) (*callbackFunc)(); \ if (callbackFunc && (liveEdit || lcd_clicked)) (*callbackFunc)(); \
if (lcd_clicked) lcd_goto_previous_menu(); \ if (lcd_clicked) lcd_goto_previous_menu(); \
@ -4857,14 +4857,14 @@ void lcd_quick_feedback(const bool clear_buttons) {
DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1); DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1);
DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1); DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1);
DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1.0); DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1);
DEFINE_MENU_EDIT_TYPE(float, float52, ftostr52, 100.0); DEFINE_MENU_EDIT_TYPE(float, float52, ftostr52, 100);
DEFINE_MENU_EDIT_TYPE(float, float43, ftostr43sign, 1000.0); DEFINE_MENU_EDIT_TYPE(float, float43, ftostr43sign, 1000);
DEFINE_MENU_EDIT_TYPE(float, float5, ftostr5rj, 0.01); DEFINE_MENU_EDIT_TYPE(float, float5, ftostr5rj, 0.01f);
DEFINE_MENU_EDIT_TYPE(float, float51, ftostr51sign, 10.0); DEFINE_MENU_EDIT_TYPE(float, float51, ftostr51sign, 10);
DEFINE_MENU_EDIT_TYPE(float, float52sign, ftostr52sign, 100.0); DEFINE_MENU_EDIT_TYPE(float, float52sign, ftostr52sign, 100);
DEFINE_MENU_EDIT_TYPE(float, float62, ftostr62rj, 100.0); DEFINE_MENU_EDIT_TYPE(float, float62, ftostr62rj, 100);
DEFINE_MENU_EDIT_TYPE(uint32_t, long5, ftostr5rj, 0.01); DEFINE_MENU_EDIT_TYPE(uint32_t, long5, ftostr5rj, 0.01f);
/** /**
* *
@ -5228,7 +5228,7 @@ void lcd_update() {
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
// loop and that the abs of the encoderDiff value is tracked. // loop and that the abs of the encoderDiff value is tracked.
float encoderStepRate = float(encoderMovementSteps) / float(ms - lastEncoderMovementMillis) * 1000.0; float encoderStepRate = float(encoderMovementSteps) / float(ms - lastEncoderMovementMillis) * 1000;
if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100;
else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;

View file

@ -69,7 +69,7 @@ vector_3 vector_3::get_normal() {
float vector_3::get_length() { return SQRT(sq(x) + sq(y) + sq(z)); } float vector_3::get_length() { return SQRT(sq(x) + sq(y) + sq(z)); }
void vector_3::normalize() { void vector_3::normalize() {
const float inv_length = 1.0 / get_length(); const float inv_length = RSQRT(sq(x) + sq(y) + sq(z));
x *= inv_length; x *= inv_length;
y *= inv_length; y *= inv_length;
z *= inv_length; z *= inv_length;

View file

@ -417,12 +417,12 @@ void MarlinSettings::postprocess() {
EEPROM_WRITE(planner.min_travel_feedrate_mm_s); EEPROM_WRITE(planner.min_travel_feedrate_mm_s);
#if ENABLED(JUNCTION_DEVIATION) #if ENABLED(JUNCTION_DEVIATION)
const float planner_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; const float planner_max_jerk[] = { float(DEFAULT_XJERK), float(DEFAULT_YJERK), float(DEFAULT_ZJERK), float(DEFAULT_EJERK) };
EEPROM_WRITE(planner_max_jerk); EEPROM_WRITE(planner_max_jerk);
EEPROM_WRITE(planner.junction_deviation_mm); EEPROM_WRITE(planner.junction_deviation_mm);
#else #else
EEPROM_WRITE(planner.max_jerk); EEPROM_WRITE(planner.max_jerk);
dummy = 0.02; dummy = 0.02f;
EEPROM_WRITE(dummy); EEPROM_WRITE(dummy);
#endif #endif
@ -488,7 +488,7 @@ void MarlinSettings::postprocess() {
#if ABL_PLANAR #if ABL_PLANAR
EEPROM_WRITE(planner.bed_level_matrix); EEPROM_WRITE(planner.bed_level_matrix);
#else #else
dummy = 0.0; dummy = 0.0f;
for (uint8_t q = 9; q--;) EEPROM_WRITE(dummy); for (uint8_t q = 9; q--;) EEPROM_WRITE(dummy);
#endif #endif
@ -974,7 +974,7 @@ void MarlinSettings::postprocess() {
eeprom_error = true; eeprom_error = true;
} }
else { else {
float dummy = 0; float dummy = 0.0f;
#if DISABLED(AUTO_BED_LEVELING_UBL) || DISABLED(FWRETRACT) || ENABLED(NO_VOLUMETRICS) #if DISABLED(AUTO_BED_LEVELING_UBL) || DISABLED(FWRETRACT) || ENABLED(NO_VOLUMETRICS)
bool dummyb; bool dummyb;
#endif #endif
@ -1733,7 +1733,7 @@ void MarlinSettings::reset(PORTARG_SOLO) {
planner.min_travel_feedrate_mm_s = DEFAULT_MINTRAVELFEEDRATE; planner.min_travel_feedrate_mm_s = DEFAULT_MINTRAVELFEEDRATE;
#if ENABLED(JUNCTION_DEVIATION) #if ENABLED(JUNCTION_DEVIATION)
planner.junction_deviation_mm = JUNCTION_DEVIATION_MM; planner.junction_deviation_mm = float(JUNCTION_DEVIATION_MM);
#else #else
planner.max_jerk[X_AXIS] = DEFAULT_XJERK; planner.max_jerk[X_AXIS] = DEFAULT_XJERK;
planner.max_jerk[Y_AXIS] = DEFAULT_YJERK; planner.max_jerk[Y_AXIS] = DEFAULT_YJERK;
@ -1835,7 +1835,7 @@ void MarlinSettings::reset(PORTARG_SOLO) {
HOTEND_LOOP() HOTEND_LOOP()
#endif #endif
{ {
PID_PARAM(Kp, e) = DEFAULT_Kp; PID_PARAM(Kp, e) = float(DEFAULT_Kp);
PID_PARAM(Ki, e) = scalePID_i(DEFAULT_Ki); PID_PARAM(Ki, e) = scalePID_i(DEFAULT_Ki);
PID_PARAM(Kd, e) = scalePID_d(DEFAULT_Kd); PID_PARAM(Kd, e) = scalePID_d(DEFAULT_Kd);
#if ENABLED(PID_EXTRUSION_SCALING) #if ENABLED(PID_EXTRUSION_SCALING)

View file

@ -90,31 +90,8 @@ void recalc_delta_settings() {
* *
* - Disable the home_offset (M206) and/or position_shift (G92) * - Disable the home_offset (M206) and/or position_shift (G92)
* features to remove up to 12 float additions. * features to remove up to 12 float additions.
*
* - Use a fast-inverse-sqrt function and add the reciprocal.
* (see above)
*/ */
#if ENABLED(DELTA_FAST_SQRT) && defined(__AVR__)
/**
* Fast inverse sqrt from Quake III Arena
* See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
*/
float Q_rsqrt(float number) {
long i;
float x2, y;
const float threehalfs = 1.5f;
x2 = number * 0.5f;
y = number;
i = * ( long * ) &y; // evil floating point bit level hacking
i = 0x5F3759DF - ( i >> 1 ); // what the f***?
y = * ( float * ) &i;
y = y * ( threehalfs - ( x2 * y * y ) ); // 1st iteration
// y = y * ( threehalfs - ( x2 * y * y ) ); // 2nd iteration, this can be removed
return y;
}
#endif
#define DELTA_DEBUG(VAR) do { \ #define DELTA_DEBUG(VAR) do { \
SERIAL_ECHOPAIR("cartesian X:", VAR[X_AXIS]); \ SERIAL_ECHOPAIR("cartesian X:", VAR[X_AXIS]); \
SERIAL_ECHOPAIR(" Y:", VAR[Y_AXIS]); \ SERIAL_ECHOPAIR(" Y:", VAR[Y_AXIS]); \
@ -178,38 +155,38 @@ float delta_safe_distance_from_top() {
* *
* The result is stored in the cartes[] array. * The result is stored in the cartes[] array.
*/ */
void forward_kinematics_DELTA(float z1, float z2, float z3) { void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3) {
// Create a vector in old coordinates along x axis of new coordinate // Create a vector in old coordinates along x axis of new coordinate
float p12[3] = { delta_tower[B_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[B_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z2 - z1 }; const float p12[3] = { delta_tower[B_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[B_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z2 - z1 };
// Get the Magnitude of vector. // Get the reciprocal of Magnitude of vector.
float d = SQRT( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) ); const float d2 = sq(p12[0]) + sq(p12[1]) + sq(p12[2]), inv_d = RSQRT(d2);
// Create unit vector by dividing by magnitude. // Create unit vector by multiplying by the inverse of the magnitude.
float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d }; const float ex[3] = { p12[0] * inv_d, p12[1] * inv_d, p12[2] * inv_d };
// Get the vector from the origin of the new system to the third point. // Get the vector from the origin of the new system to the third point.
float p13[3] = { delta_tower[C_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[C_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z3 - z1 }; const float p13[3] = { delta_tower[C_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[C_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z3 - z1 };
// Use the dot product to find the component of this vector on the X axis. // Use the dot product to find the component of this vector on the X axis.
float i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2]; const float i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2];
// Create a vector along the x axis that represents the x component of p13. // Create a vector along the x axis that represents the x component of p13.
float iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i }; const float iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i };
// Subtract the X component from the original vector leaving only Y. We use the // Subtract the X component from the original vector leaving only Y. We use the
// variable that will be the unit vector after we scale it. // variable that will be the unit vector after we scale it.
float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] }; float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
// The magnitude of Y component // The magnitude and the inverse of the magnitude of Y component
float j = SQRT( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) ); const float j2 = sq(ey[0]) + sq(ey[1]) + sq(ey[2]), inv_j = RSQRT(j2);
// Convert to a unit vector // Convert to a unit vector
ey[0] /= j; ey[1] /= j; ey[2] /= j; ey[0] *= inv_j; ey[1] *= inv_j; ey[2] *= inv_j;
// The cross product of the unit x and y is the unit z // The cross product of the unit x and y is the unit z
// float[] ez = vectorCrossProd(ex, ey); // float[] ez = vectorCrossProd(ex, ey);
float ez[3] = { const float ez[3] = {
ex[1] * ey[2] - ex[2] * ey[1], ex[1] * ey[2] - ex[2] * ey[1],
ex[2] * ey[0] - ex[0] * ey[2], ex[2] * ey[0] - ex[0] * ey[2],
ex[0] * ey[1] - ex[1] * ey[0] ex[0] * ey[1] - ex[1] * ey[0]
@ -217,16 +194,16 @@ void forward_kinematics_DELTA(float z1, float z2, float z3) {
// We now have the d, i and j values defined in Wikipedia. // We now have the d, i and j values defined in Wikipedia.
// Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + sq(d)) / (d * 2), const float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + d2) * inv_d * 0.5,
Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + HYPOT2(i, j)) / 2 - i * Xnew) / j, Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + sq(i) + j2) * 0.5 - i * Xnew) * inv_j,
Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew)); Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew));
// Start from the origin of the old coordinates and add vectors in the // Start from the origin of the old coordinates and add vectors in the
// old coords that represent the Xnew, Ynew and Znew to find the point // old coords that represent the Xnew, Ynew and Znew to find the point
// in the old system. // in the old system.
cartes[X_AXIS] = delta_tower[A_AXIS][X_AXIS] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew; cartes[X_AXIS] = delta_tower[A_AXIS][X_AXIS] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew;
cartes[Y_AXIS] = delta_tower[A_AXIS][Y_AXIS] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew; cartes[Y_AXIS] = delta_tower[A_AXIS][Y_AXIS] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew;
cartes[Z_AXIS] = z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew; cartes[Z_AXIS] = z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew;
} }
#if ENABLED(SENSORLESS_HOMING) #if ENABLED(SENSORLESS_HOMING)

View file

@ -64,26 +64,15 @@ void recalc_delta_settings();
* (see above) * (see above)
*/ */
#if ENABLED(DELTA_FAST_SQRT) && defined(__AVR__)
/**
* Fast inverse sqrt from Quake III Arena
* See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
*/
float Q_rsqrt(float number);
#define _SQRT(n) (1.0f / Q_rsqrt(n))
#else
#define _SQRT(n) SQRT(n)
#endif
// Macro to obtain the Z position of an individual tower // Macro to obtain the Z position of an individual tower
#define DELTA_Z(V,T) V[Z_AXIS] + _SQRT( \ #define DELTA_Z(V,T) V[Z_AXIS] + SQRT( \
delta_diagonal_rod_2_tower[T] - HYPOT2( \ delta_diagonal_rod_2_tower[T] - HYPOT2( \
delta_tower[T][X_AXIS] - V[X_AXIS], \ delta_tower[T][X_AXIS] - V[X_AXIS], \
delta_tower[T][Y_AXIS] - V[Y_AXIS] \ delta_tower[T][Y_AXIS] - V[Y_AXIS] \
) \ ) \
) )
#define DELTA_IK(V) do { \ #define DELTA_IK(V) do { \
delta[A_AXIS] = DELTA_Z(V, A_AXIS); \ delta[A_AXIS] = DELTA_Z(V, A_AXIS); \
delta[B_AXIS] = DELTA_Z(V, B_AXIS); \ delta[B_AXIS] = DELTA_Z(V, B_AXIS); \
delta[C_AXIS] = DELTA_Z(V, C_AXIS); \ delta[C_AXIS] = DELTA_Z(V, C_AXIS); \
@ -122,9 +111,9 @@ float delta_safe_distance_from_top();
* *
* The result is stored in the cartes[] array. * The result is stored in the cartes[] array.
*/ */
void forward_kinematics_DELTA(float z1, float z2, float z3); void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3);
FORCE_INLINE void forward_kinematics_DELTA(float point[ABC]) { FORCE_INLINE void forward_kinematics_DELTA(const float (&point)[ABC]) {
forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]); forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]);
} }

View file

@ -77,7 +77,7 @@ bool relative_mode; // = false;
* Used by 'buffer_line_to_current_position' to do a move after changing it. * Used by 'buffer_line_to_current_position' to do a move after changing it.
* Used by 'SYNC_PLAN_POSITION_KINEMATIC' to update 'planner.position'. * Used by 'SYNC_PLAN_POSITION_KINEMATIC' to update 'planner.position'.
*/ */
float current_position[XYZE] = { 0.0 }; float current_position[XYZE] = { 0 };
/** /**
* Cartesian Destination * Cartesian Destination
@ -85,7 +85,7 @@ float current_position[XYZE] = { 0.0 };
* and expected by functions like 'prepare_move_to_destination'. * and expected by functions like 'prepare_move_to_destination'.
* Set with 'get_destination_from_command' or 'set_destination_from_current'. * Set with 'get_destination_from_command' or 'set_destination_from_current'.
*/ */
float destination[XYZE] = { 0.0 }; float destination[XYZE] = { 0 };
// The active extruder (tool). Set with T<extruder> command. // The active extruder (tool). Set with T<extruder> command.
@ -100,7 +100,7 @@ uint8_t active_extruder; // = 0;
// no other feedrate is specified. Overridden for special moves. // no other feedrate is specified. Overridden for special moves.
// Set by the last G0 through G5 command's "F" parameter. // Set by the last G0 through G5 command's "F" parameter.
// Functions that override this for custom moves *must always* restore it! // Functions that override this for custom moves *must always* restore it!
float feedrate_mm_s = MMM_TO_MMS(1500.0); float feedrate_mm_s = MMM_TO_MMS(1500.0f);
int16_t feedrate_percentage = 100; int16_t feedrate_percentage = 100;
@ -509,7 +509,7 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
* but may produce jagged lines. Try 0.5mm, 1.0mm, and 2.0mm * but may produce jagged lines. Try 0.5mm, 1.0mm, and 2.0mm
* and compare the difference. * and compare the difference.
*/ */
#define SCARA_MIN_SEGMENT_LENGTH 0.5 #define SCARA_MIN_SEGMENT_LENGTH 0.5f
#endif #endif
/** /**
@ -566,14 +566,14 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
// For SCARA enforce a minimum segment size // For SCARA enforce a minimum segment size
#if IS_SCARA #if IS_SCARA
NOMORE(segments, cartesian_mm * (1.0 / SCARA_MIN_SEGMENT_LENGTH)); NOMORE(segments, cartesian_mm * (1.0f / float(SCARA_MIN_SEGMENT_LENGTH)));
#endif #endif
// At least one segment is required // At least one segment is required
NOLESS(segments, 1U); NOLESS(segments, 1U);
// The approximate length of each segment // The approximate length of each segment
const float inv_segments = 1.0 / float(segments), const float inv_segments = 1.0f / float(segments),
segment_distance[XYZE] = { segment_distance[XYZE] = {
xdiff * inv_segments, xdiff * inv_segments,
ydiff * inv_segments, ydiff * inv_segments,
@ -599,7 +599,7 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
// SCARA needs to scale the feed rate from mm/s to degrees/s // SCARA needs to scale the feed rate from mm/s to degrees/s
// i.e., Complete the angular vector in the given time. // i.e., Complete the angular vector in the given time.
const float segment_length = cartesian_mm * inv_segments, const float segment_length = cartesian_mm * inv_segments,
inv_segment_length = 1.0 / segment_length, // 1/mm/segs inv_segment_length = 1.0f / segment_length, // 1/mm/segs
inverse_secs = inv_segment_length * _feedrate_mm_s; inverse_secs = inv_segment_length * _feedrate_mm_s;
float oldA = planner.position_float[A_AXIS], float oldA = planner.position_float[A_AXIS],
@ -756,7 +756,7 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
NOLESS(segments, 1U); NOLESS(segments, 1U);
// The approximate length of each segment // The approximate length of each segment
const float inv_segments = 1.0 / float(segments), const float inv_segments = 1.0f / float(segments),
cartesian_segment_mm = cartesian_mm * inv_segments, cartesian_segment_mm = cartesian_mm * inv_segments,
segment_distance[XYZE] = { segment_distance[XYZE] = {
xdiff * inv_segments, xdiff * inv_segments,
@ -1335,7 +1335,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(DEBUG_LEVELING_FEATURE) #if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 1 Fast:"); if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 1 Fast:");
#endif #endif
do_homing_move(axis, 1.5 * max_length(axis) * axis_home_dir); do_homing_move(axis, 1.5f * max_length(axis) * axis_home_dir);
// 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 * (

View file

@ -71,7 +71,7 @@ extern float feedrate_mm_s;
* Feedrate scaling and conversion * Feedrate scaling and conversion
*/ */
extern int16_t feedrate_percentage; extern int16_t feedrate_percentage;
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01) #define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01f)
extern uint8_t active_extruder; extern uint8_t active_extruder;
@ -141,7 +141,7 @@ void line_to_current_position();
void buffer_line_to_destination(const float fr_mm_s); void buffer_line_to_destination(const float fr_mm_s);
#if IS_KINEMATIC #if IS_KINEMATIC
void prepare_uninterpolated_move_to_destination(const float fr_mm_s=0.0); void prepare_uninterpolated_move_to_destination(const float fr_mm_s=0);
#endif #endif
void prepare_move_to_destination(); void prepare_move_to_destination();
@ -149,10 +149,10 @@ void prepare_move_to_destination();
/** /**
* Blocking movement and shorthand functions * Blocking movement and shorthand functions
*/ */
void do_blocking_move_to(const float rx, const float ry, const float rz, const float &fr_mm_s=0.0); void do_blocking_move_to(const float rx, const float ry, const float rz, const float &fr_mm_s=0);
void do_blocking_move_to_x(const float &rx, const float &fr_mm_s=0.0); void do_blocking_move_to_x(const float &rx, const float &fr_mm_s=0);
void do_blocking_move_to_z(const float &rz, const float &fr_mm_s=0.0); void do_blocking_move_to_z(const float &rz, const float &fr_mm_s=0);
void do_blocking_move_to_xy(const float &rx, const float &ry, const float &fr_mm_s=0.0); void do_blocking_move_to_xy(const float &rx, const float &ry, const float &fr_mm_s=0);
void setup_for_endstop_or_probe_move(); void setup_for_endstop_or_probe_move();
void clean_up_after_endstop_or_probe_move(); void clean_up_after_endstop_or_probe_move();
@ -268,8 +268,8 @@ void homeaxis(const AxisEnum axis);
// Return true if the given position is within the machine bounds. // Return true if the given position is within the machine bounds.
inline bool position_is_reachable(const float &rx, const float &ry) { inline bool position_is_reachable(const float &rx, const float &ry) {
// Add 0.001 margin to deal with float imprecision // Add 0.001 margin to deal with float imprecision
return WITHIN(rx, X_MIN_POS - 0.001, X_MAX_POS + 0.001) return WITHIN(rx, X_MIN_POS - 0.001f, X_MAX_POS + 0.001f)
&& WITHIN(ry, Y_MIN_POS - 0.001, Y_MAX_POS + 0.001); && WITHIN(ry, Y_MIN_POS - 0.001f, Y_MAX_POS + 0.001f);
} }
#if HAS_BED_PROBE #if HAS_BED_PROBE
@ -282,8 +282,8 @@ void homeaxis(const AxisEnum axis);
*/ */
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))
&& WITHIN(rx, MIN_PROBE_X - 0.001, MAX_PROBE_X + 0.001) && WITHIN(rx, MIN_PROBE_X - 0.001f, MAX_PROBE_X + 0.001f)
&& WITHIN(ry, MIN_PROBE_Y - 0.001, MAX_PROBE_Y + 0.001); && WITHIN(ry, MIN_PROBE_Y - 0.001f, MAX_PROBE_Y + 0.001f);
} }
#endif #endif

View file

@ -150,11 +150,11 @@ float Planner::max_feedrate_mm_s[XYZE_N], // (mm/s) M203 XYZE - Max speeds
int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder
float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0); // The flow percentage and volumetric multiplier combine to scale E movement float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement
#if DISABLED(NO_VOLUMETRICS) #if DISABLED(NO_VOLUMETRICS)
float Planner::filament_size[EXTRUDERS], // diameter of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder float Planner::filament_size[EXTRUDERS], // diameter of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder
Planner::volumetric_area_nominal = CIRCLE_AREA((DEFAULT_NOMINAL_FILAMENT_DIA) * 0.5), // Nominal cross-sectional area Planner::volumetric_area_nominal = CIRCLE_AREA((float(DEFAULT_NOMINAL_FILAMENT_DIA)) * 0.5f), // Nominal cross-sectional area
Planner::volumetric_multiplier[EXTRUDERS]; // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner Planner::volumetric_multiplier[EXTRUDERS]; // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner
#endif #endif
@ -188,7 +188,7 @@ float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0); // The flow perce
#if ENABLED(AUTOTEMP) #if ENABLED(AUTOTEMP)
float Planner::autotemp_max = 250, float Planner::autotemp_max = 250,
Planner::autotemp_min = 210, Planner::autotemp_min = 210,
Planner::autotemp_factor = 0.1; Planner::autotemp_factor = 0.1f;
bool Planner::autotemp_enabled = false; bool Planner::autotemp_enabled = false;
#endif #endif
@ -236,7 +236,7 @@ void Planner::init() {
ZERO(position_float); ZERO(position_float);
#endif #endif
ZERO(previous_speed); ZERO(previous_speed);
previous_nominal_speed_sqr = 0.0; previous_nominal_speed_sqr = 0;
#if ABL_PLANAR #if ABL_PLANAR
bed_level_matrix.set_to_identity(); bed_level_matrix.set_to_identity();
#endif #endif
@ -859,7 +859,7 @@ void Planner::reverse_pass_kernel(block_t* const current, const block_t * const
const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH) const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
? max_entry_speed_sqr ? max_entry_speed_sqr
: MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(MINIMUM_PLANNER_SPEED), current->millimeters)); : MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(float(MINIMUM_PLANNER_SPEED)), current->millimeters));
if (current->entry_speed_sqr != new_entry_speed_sqr) { if (current->entry_speed_sqr != new_entry_speed_sqr) {
// Need to recalculate the block speed - Mark it now, so the stepper // Need to recalculate the block speed - Mark it now, so the stepper
@ -1076,7 +1076,7 @@ void Planner::recalculate_trapezoids() {
// NOTE: Entry and exit factors always > 0 by all previous logic operations. // NOTE: Entry and exit factors always > 0 by all previous logic operations.
const float current_nominal_speed = SQRT(current->nominal_speed_sqr), const float current_nominal_speed = SQRT(current->nominal_speed_sqr),
nomr = 1.0 / current_nominal_speed; nomr = 1.0f / current_nominal_speed;
calculate_trapezoid_for_block(current, current_entry_speed * nomr, next_entry_speed * nomr); calculate_trapezoid_for_block(current, current_entry_speed * nomr, next_entry_speed * nomr);
#if ENABLED(LIN_ADVANCE) #if ENABLED(LIN_ADVANCE)
if (current->use_advance_lead) { if (current->use_advance_lead) {
@ -1115,8 +1115,8 @@ void Planner::recalculate_trapezoids() {
// Block is not BUSY, we won the race against the Stepper ISR: // Block is not BUSY, we won the race against the Stepper ISR:
const float next_nominal_speed = SQRT(next->nominal_speed_sqr), const float next_nominal_speed = SQRT(next->nominal_speed_sqr),
nomr = 1.0 / next_nominal_speed; nomr = 1.0f / next_nominal_speed;
calculate_trapezoid_for_block(next, next_entry_speed * nomr, (MINIMUM_PLANNER_SPEED) * nomr); calculate_trapezoid_for_block(next, next_entry_speed * nomr, float(MINIMUM_PLANNER_SPEED) * nomr);
#if ENABLED(LIN_ADVANCE) #if ENABLED(LIN_ADVANCE)
if (next->use_advance_lead) { if (next->use_advance_lead) {
const float comp = next->e_D_ratio * extruder_advance_K * axis_steps_per_mm[E_AXIS]; const float comp = next->e_D_ratio * extruder_advance_K * axis_steps_per_mm[E_AXIS];
@ -1162,7 +1162,7 @@ void Planner::recalculate() {
float t = autotemp_min + high * autotemp_factor; float t = autotemp_min + high * autotemp_factor;
t = constrain(t, autotemp_min, autotemp_max); t = constrain(t, autotemp_min, autotemp_max);
if (t < oldt) t = t * (1 - (AUTOTEMP_OLDWEIGHT)) + oldt * (AUTOTEMP_OLDWEIGHT); if (t < oldt) t = t * (1 - float(AUTOTEMP_OLDWEIGHT)) + oldt * float(AUTOTEMP_OLDWEIGHT);
oldt = t; oldt = t;
thermalManager.setTargetHotend(t, 0); thermalManager.setTargetHotend(t, 0);
} }
@ -1317,7 +1317,7 @@ void Planner::check_axes_activity() {
* Return 1.0 with volumetric off or a diameter of 0.0. * Return 1.0 with volumetric off or a diameter of 0.0.
*/ */
inline float calculate_volumetric_multiplier(const float &diameter) { inline float calculate_volumetric_multiplier(const float &diameter) {
return (parser.volumetric_enabled && diameter) ? 1.0 / CIRCLE_AREA(diameter * 0.5) : 1.0; return (parser.volumetric_enabled && diameter) ? RECIPROCAL(CIRCLE_AREA(diameter * 0.5f)) : 1;
} }
/** /**
@ -1341,11 +1341,11 @@ void Planner::check_axes_activity() {
*/ */
void Planner::calculate_volumetric_for_width_sensor(const int8_t encoded_ratio) { void Planner::calculate_volumetric_for_width_sensor(const int8_t encoded_ratio) {
// Reconstitute the nominal/measured ratio // Reconstitute the nominal/measured ratio
const float nom_meas_ratio = 1.0 + 0.01 * encoded_ratio, const float nom_meas_ratio = 1 + 0.01f * encoded_ratio,
ratio_2 = sq(nom_meas_ratio); ratio_2 = sq(nom_meas_ratio);
volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] = parser.volumetric_enabled volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] = parser.volumetric_enabled
? ratio_2 / CIRCLE_AREA(filament_width_nominal * 0.5) // Volumetric uses a true volumetric multiplier ? ratio_2 / CIRCLE_AREA(filament_width_nominal * 0.5f) // Volumetric uses a true volumetric multiplier
: ratio_2; // Linear squares the ratio, which scales the volume : ratio_2; // Linear squares the ratio, which scales the volume
refresh_e_factor(FILAMENT_SENSOR_EXTRUDER_NUM); refresh_e_factor(FILAMENT_SENSOR_EXTRUDER_NUM);
@ -1690,7 +1690,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
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 uint32_t esteps = ABS(esteps_float) + 0.5; const uint32_t esteps = ABS(esteps_float) + 0.5f;
// Clear all flags, including the "busy" bit // Clear all flags, including the "busy" bit
block->flag = 0x00; block->flag = 0x00;
@ -1957,7 +1957,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill
#if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT) #if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT)
// Segment time im micro seconds // Segment time im micro seconds
uint32_t segment_time_us = LROUND(1000000.0 / inverse_secs); uint32_t segment_time_us = LROUND(1000000.0f / inverse_secs);
#endif #endif
#if ENABLED(SLOWDOWN) #if ENABLED(SLOWDOWN)
@ -1965,7 +1965,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
if (segment_time_us < min_segment_time_us) { if (segment_time_us < min_segment_time_us) {
// buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more. // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more.
const uint32_t nst = segment_time_us + LROUND(2 * (min_segment_time_us - segment_time_us) / moves_queued); const uint32_t nst = segment_time_us + LROUND(2 * (min_segment_time_us - segment_time_us) / moves_queued);
inverse_secs = 1000000.0 / nst; inverse_secs = 1000000.0f / nst;
#if defined(XY_FREQUENCY_LIMIT) || ENABLED(ULTRA_LCD) #if defined(XY_FREQUENCY_LIMIT) || ENABLED(ULTRA_LCD)
segment_time_us = nst; segment_time_us = nst;
#endif #endif
@ -2005,7 +2005,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
while (filwidth_delay_dist >= MMD_MM) filwidth_delay_dist -= MMD_MM; while (filwidth_delay_dist >= MMD_MM) filwidth_delay_dist -= MMD_MM;
// Convert into an index into the measurement array // Convert into an index into the measurement array
filwidth_delay_index[0] = int8_t(filwidth_delay_dist * 0.1); filwidth_delay_index[0] = int8_t(filwidth_delay_dist * 0.1f);
// If the index has changed (must have gone forward)... // If the index has changed (must have gone forward)...
if (filwidth_delay_index[0] != filwidth_delay_index[1]) { if (filwidth_delay_index[0] != filwidth_delay_index[1]) {
@ -2021,7 +2021,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
#endif #endif
// 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.0f; // factor <1 decreases speed
LOOP_XYZE(i) { LOOP_XYZE(i) {
const float cs = ABS((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)
@ -2069,7 +2069,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
#endif // XY_FREQUENCY_LIMIT #endif // XY_FREQUENCY_LIMIT
// Correct the speed // Correct the speed
if (speed_factor < 1.0) { if (speed_factor < 1.0f) {
LOOP_XYZE(i) current_speed[i] *= speed_factor; LOOP_XYZE(i) current_speed[i] *= speed_factor;
block->nominal_rate *= speed_factor; block->nominal_rate *= speed_factor;
block->nominal_speed_sqr = block->nominal_speed_sqr * sq(speed_factor); block->nominal_speed_sqr = block->nominal_speed_sqr * sq(speed_factor);
@ -2142,7 +2142,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// Check for unusual high e_D ratio to detect if a retract move was combined with the last print move due to min. steps per segment. Never execute this with advance! // Check for unusual high e_D ratio to detect if a retract move was combined with the last print move due to min. steps per segment. Never execute this with advance!
// This assumes no one will use a retract length of 0mm < retr_length < ~0.2mm and no one will print 100mm wide lines using 3mm filament or 35mm wide lines using 1.75mm filament. // This assumes no one will use a retract length of 0mm < retr_length < ~0.2mm and no one will print 100mm wide lines using 3mm filament or 35mm wide lines using 1.75mm filament.
if (block->e_D_ratio > 3.0) if (block->e_D_ratio > 3.0f)
block->use_advance_lead = false; block->use_advance_lead = false;
else { else {
const uint32_t max_accel_steps_per_s2 = MAX_E_JERK / (extruder_advance_K * block->e_D_ratio) * steps_per_mm; const uint32_t max_accel_steps_per_s2 = MAX_E_JERK / (extruder_advance_K * block->e_D_ratio) * steps_per_mm;
@ -2177,7 +2177,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
block->acceleration_steps_per_s2 = accel; block->acceleration_steps_per_s2 = accel;
block->acceleration = accel / steps_per_mm; block->acceleration = accel / steps_per_mm;
#if DISABLED(S_CURVE_ACCELERATION) #if DISABLED(S_CURVE_ACCELERATION)
block->acceleration_rate = (uint32_t)(accel * (4096.0 * 4096.0 / (STEPPER_TIMER_RATE))); block->acceleration_rate = (uint32_t)(accel * (4096.0f * 4096.0f / (STEPPER_TIMER_RATE)));
#endif #endif
#if ENABLED(LIN_ADVANCE) #if ENABLED(LIN_ADVANCE)
if (block->use_advance_lead) { if (block->use_advance_lead) {
@ -2250,12 +2250,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
; ;
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
if (junction_cos_theta > 0.999999) { if (junction_cos_theta > 0.999999f) {
// For a 0 degree acute junction, just set minimum junction speed. // For a 0 degree acute junction, just set minimum junction speed.
vmax_junction_sqr = sq(MINIMUM_PLANNER_SPEED); vmax_junction_sqr = sq(float(MINIMUM_PLANNER_SPEED));
} }
else { else {
NOLESS(junction_cos_theta, -0.999999); // Check for numerical round-off to avoid divide by zero. NOLESS(junction_cos_theta, -0.999999f); // Check for numerical round-off to avoid divide by zero.
// Convert delta vector to unit vector // Convert delta vector to unit vector
float junction_unit_vec[XYZE] = { float junction_unit_vec[XYZE] = {
@ -2267,13 +2267,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
normalize_junction_vector(junction_unit_vec); normalize_junction_vector(junction_unit_vec);
const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec), const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec),
sin_theta_d2 = SQRT(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive. sin_theta_d2 = SQRT(0.5f * (1.0f - junction_cos_theta)); // Trig half angle identity. Always positive.
vmax_junction_sqr = (junction_acceleration * junction_deviation_mm * sin_theta_d2) / (1.0 - sin_theta_d2); vmax_junction_sqr = (junction_acceleration * junction_deviation_mm * sin_theta_d2) / (1.0f - sin_theta_d2);
if (block->millimeters < 1.0) { if (block->millimeters < 1) {
// Fast acos approximation, minus the error bar to be safe // Fast acos approximation, minus the error bar to be safe
const float junction_theta = (RADIANS(-40) * sq(junction_cos_theta) - RADIANS(50)) * junction_cos_theta + RADIANS(90) - 0.18; const float junction_theta = (RADIANS(-40) * sq(junction_cos_theta) - RADIANS(50)) * junction_cos_theta + RADIANS(90) - 0.18f;
// If angle is greater than 135 degrees (octagon), find speed for approximate arc // If angle is greater than 135 degrees (octagon), find speed for approximate arc
if (junction_theta > RADIANS(135)) { if (junction_theta > RADIANS(135)) {
@ -2287,7 +2287,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
vmax_junction_sqr = MIN3(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr); vmax_junction_sqr = MIN3(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr);
} }
else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later. else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later.
vmax_junction_sqr = 0.0; vmax_junction_sqr = 0;
COPY(previous_unit_vec, unit_vec); COPY(previous_unit_vec, unit_vec);
@ -2378,11 +2378,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
block->max_entry_speed_sqr = vmax_junction_sqr; block->max_entry_speed_sqr = vmax_junction_sqr;
// Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED. // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED.
const float v_allowable_sqr = max_allowable_speed_sqr(-block->acceleration, sq(MINIMUM_PLANNER_SPEED), block->millimeters); const float v_allowable_sqr = max_allowable_speed_sqr(-block->acceleration, sq(float(MINIMUM_PLANNER_SPEED)), block->millimeters);
// If we are trying to add a split block, start with the // If we are trying to add a split block, start with the
// max. allowed speed to avoid an interrupted first move. // max. allowed speed to avoid an interrupted first move.
block->entry_speed_sqr = !split_move ? sq(MINIMUM_PLANNER_SPEED) : MIN(vmax_junction_sqr, v_allowable_sqr); block->entry_speed_sqr = !split_move ? sq(float(MINIMUM_PLANNER_SPEED)) : MIN(vmax_junction_sqr, v_allowable_sqr);
// 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

@ -324,7 +324,7 @@ class Planner {
static void refresh_positioning(); static void refresh_positioning();
FORCE_INLINE static void refresh_e_factor(const uint8_t e) { FORCE_INLINE static void refresh_e_factor(const uint8_t e) {
e_factor[e] = (flow_percentage[e] * 0.01 e_factor[e] = (flow_percentage[e] * 0.01f
#if DISABLED(NO_VOLUMETRICS) #if DISABLED(NO_VOLUMETRICS)
* volumetric_multiplier[e] * volumetric_multiplier[e]
#endif #endif
@ -362,19 +362,19 @@ class Planner {
* Returns 0.0 if Z is past the specified 'Fade Height'. * Returns 0.0 if Z is past the specified 'Fade Height'.
*/ */
inline static float fade_scaling_factor_for_z(const float &rz) { inline static float fade_scaling_factor_for_z(const float &rz) {
static float z_fade_factor = 1.0; static float z_fade_factor = 1;
if (z_fade_height) { if (z_fade_height) {
if (rz >= z_fade_height) return 0.0; if (rz >= z_fade_height) return 0;
if (last_fade_z != rz) { if (last_fade_z != rz) {
last_fade_z = rz; last_fade_z = rz;
z_fade_factor = 1.0 - rz * inverse_z_fade_height; z_fade_factor = 1 - rz * inverse_z_fade_height;
} }
return z_fade_factor; return z_fade_factor;
} }
return 1.0; return 1;
} }
FORCE_INLINE static void force_fade_recalc() { last_fade_z = -999.999; } FORCE_INLINE static void force_fade_recalc() { last_fade_z = -999.999f; }
FORCE_INLINE static void set_z_fade_height(const float &zfh) { FORCE_INLINE static void set_z_fade_height(const float &zfh) {
z_fade_height = zfh > 0 ? zfh : 0; z_fade_height = zfh > 0 ? zfh : 0;
@ -390,7 +390,7 @@ class Planner {
FORCE_INLINE static float fade_scaling_factor_for_z(const float &rz) { FORCE_INLINE static float fade_scaling_factor_for_z(const float &rz) {
UNUSED(rz); UNUSED(rz);
return 1.0; return 1;
} }
FORCE_INLINE static bool leveling_active_at_z(const float &rz) { UNUSED(rz); return true; } FORCE_INLINE static bool leveling_active_at_z(const float &rz) { UNUSED(rz); return true; }
@ -831,9 +831,9 @@ class Planner {
#if ENABLED(JUNCTION_DEVIATION) #if ENABLED(JUNCTION_DEVIATION)
FORCE_INLINE static void normalize_junction_vector(float (&vector)[XYZE]) { FORCE_INLINE static void normalize_junction_vector(float (&vector)[XYZE]) {
float magnitude_sq = 0.0; float magnitude_sq = 0;
LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]); LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]);
const float inv_magnitude = 1.0 / SQRT(magnitude_sq); const float inv_magnitude = RSQRT(magnitude_sq);
LOOP_XYZE(idx) vector[idx] *= inv_magnitude; LOOP_XYZE(idx) vector[idx] *= inv_magnitude;
} }

View file

@ -40,12 +40,12 @@
#include "../gcode/queue.h" #include "../gcode/queue.h"
// See the meaning in the documentation of cubic_b_spline(). // See the meaning in the documentation of cubic_b_spline().
#define MIN_STEP 0.002 #define MIN_STEP 0.002f
#define MAX_STEP 0.1 #define MAX_STEP 0.1f
#define SIGMA 0.1 #define SIGMA 0.1f
// Compute the linear interpolation between two real numbers. // Compute the linear interpolation between two real numbers.
inline static float interp(float a, float b, float t) { return (1.0 - t) * a + t * b; } inline static float interp(float a, float b, float t) { return (1 - t) * a + t * b; }
/** /**
* Compute a Bézier curve using the De Casteljau's algorithm (see * Compute a Bézier curve using the De Casteljau's algorithm (see
@ -114,7 +114,7 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
first1 = position[Y_AXIS] + offset[1], first1 = position[Y_AXIS] + offset[1],
second0 = target[X_AXIS] + offset[2], second0 = target[X_AXIS] + offset[2],
second1 = target[Y_AXIS] + offset[3]; second1 = target[Y_AXIS] + offset[3];
float t = 0.0; float t = 0;
float bez_target[4]; float bez_target[4];
bez_target[X_AXIS] = position[X_AXIS]; bez_target[X_AXIS] = position[X_AXIS];
@ -123,7 +123,7 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
millis_t next_idle_ms = millis() + 200UL; millis_t next_idle_ms = millis() + 200UL;
while (t < 1.0) { while (t < 1) {
thermalManager.manage_heater(); thermalManager.manage_heater();
millis_t now = millis(); millis_t now = millis();
@ -136,16 +136,16 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
// close to a linear interpolation. // close to a linear interpolation.
bool did_reduce = false; bool did_reduce = false;
float new_t = t + step; float new_t = t + step;
NOMORE(new_t, 1.0); NOMORE(new_t, 1);
float new_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], new_t), float new_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], new_t),
new_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], new_t); new_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], new_t);
for (;;) { for (;;) {
if (new_t - t < (MIN_STEP)) break; if (new_t - t < (MIN_STEP)) break;
const float candidate_t = 0.5 * (t + new_t), const float candidate_t = 0.5f * (t + new_t),
candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t), candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t), candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
interp_pos0 = 0.5 * (bez_target[X_AXIS] + new_pos0), interp_pos0 = 0.5f * (bez_target[X_AXIS] + new_pos0),
interp_pos1 = 0.5 * (bez_target[Y_AXIS] + new_pos1); interp_pos1 = 0.5f * (bez_target[Y_AXIS] + new_pos1);
if (dist1(candidate_pos0, candidate_pos1, interp_pos0, interp_pos1) <= (SIGMA)) break; if (dist1(candidate_pos0, candidate_pos1, interp_pos0, interp_pos1) <= (SIGMA)) break;
new_t = candidate_t; new_t = candidate_t;
new_pos0 = candidate_pos0; new_pos0 = candidate_pos0;
@ -156,12 +156,12 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
// If we did not reduce the step, maybe we should enlarge it. // If we did not reduce the step, maybe we should enlarge it.
if (!did_reduce) for (;;) { if (!did_reduce) for (;;) {
if (new_t - t > MAX_STEP) break; if (new_t - t > MAX_STEP) break;
const float candidate_t = t + 2.0 * (new_t - t); const float candidate_t = t + 2 * (new_t - t);
if (candidate_t >= 1.0) break; if (candidate_t >= 1) break;
const float candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t), const float candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t), candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
interp_pos0 = 0.5 * (bez_target[X_AXIS] + candidate_pos0), interp_pos0 = 0.5f * (bez_target[X_AXIS] + candidate_pos0),
interp_pos1 = 0.5 * (bez_target[Y_AXIS] + candidate_pos1); interp_pos1 = 0.5f * (bez_target[Y_AXIS] + candidate_pos1);
if (dist1(new_pos0, new_pos1, interp_pos0, interp_pos1) > (SIGMA)) break; if (dist1(new_pos0, new_pos1, interp_pos0, interp_pos1) > (SIGMA)) break;
new_t = candidate_t; new_t = candidate_t;
new_pos0 = candidate_pos0; new_pos0 = candidate_pos0;

View file

@ -53,7 +53,7 @@ millis_t PrintCounter::deltaDuration() {
return lastDuration - tmp; return lastDuration - tmp;
} }
void PrintCounter::incFilamentUsed(double const &amount) { void PrintCounter::incFilamentUsed(float const &amount) {
#if ENABLED(DEBUG_PRINTCOUNTER) #if ENABLED(DEBUG_PRINTCOUNTER)
debug(PSTR("incFilamentUsed")); debug(PSTR("incFilamentUsed"));
#endif #endif

View file

@ -37,13 +37,13 @@
#define STATS_EEPROM_ADDRESS 0x32 #define STATS_EEPROM_ADDRESS 0x32
#endif #endif
struct printStatistics { // 16 bytes (20 with real doubles) struct printStatistics { // 16 bytes
//const uint8_t magic; // Magic header, it will always be 0x16 //const uint8_t magic; // Magic header, it will always be 0x16
uint16_t totalPrints; // Number of prints uint16_t totalPrints; // Number of prints
uint16_t finishedPrints; // Number of complete prints uint16_t finishedPrints; // Number of complete prints
uint32_t printTime; // Accumulated printing time uint32_t printTime; // Accumulated printing time
uint32_t longestPrint; // Longest successful print job uint32_t longestPrint; // Longest successful print job
double filamentUsed; // Accumulated filament consumed in mm float filamentUsed; // Accumulated filament consumed in mm
}; };
class PrintCounter: public Stopwatch { class PrintCounter: public Stopwatch {
@ -128,7 +128,7 @@ class PrintCounter: public Stopwatch {
* *
* @param amount The amount of filament used in mm * @param amount The amount of filament used in mm
*/ */
static void incFilamentUsed(double const &amount); static void incFilamentUsed(float const &amount);
/** /**
* @brief Reset the Print Statistics * @brief Reset the Print Statistics

View file

@ -625,7 +625,7 @@ static float run_z_probe() {
#if MULTIPLE_PROBING > 2 #if MULTIPLE_PROBING > 2
// Return the average value of all probes // Return the average value of all probes
const float measured_z = probes_total * (1.0 / (MULTIPLE_PROBING)); const float measured_z = probes_total * (1.0f / (MULTIPLE_PROBING));
#elif MULTIPLE_PROBING == 2 #elif MULTIPLE_PROBING == 2

View file

@ -393,13 +393,13 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS];
SERIAL_PROTOCOLPAIR(MSG_T_MIN, min); SERIAL_PROTOCOLPAIR(MSG_T_MIN, min);
SERIAL_PROTOCOLPAIR(MSG_T_MAX, max); SERIAL_PROTOCOLPAIR(MSG_T_MAX, max);
if (cycles > 2) { if (cycles > 2) {
Ku = (4.0 * d) / (M_PI * (max - min) * 0.5); Ku = (4.0f * d) / (float(M_PI) * (max - min) * 0.5f);
Tu = ((float)(t_low + t_high) * 0.001); Tu = ((float)(t_low + t_high) * 0.001f);
SERIAL_PROTOCOLPAIR(MSG_KU, Ku); SERIAL_PROTOCOLPAIR(MSG_KU, Ku);
SERIAL_PROTOCOLPAIR(MSG_TU, Tu); SERIAL_PROTOCOLPAIR(MSG_TU, Tu);
workKp = 0.6 * Ku; workKp = 0.6f * Ku;
workKi = 2 * workKp / Tu; workKi = 2 * workKp / Tu;
workKd = workKp * Tu * 0.125; workKd = workKp * Tu * 0.125f;
SERIAL_PROTOCOLLNPGM("\n" MSG_CLASSIC_PID); SERIAL_PROTOCOLLNPGM("\n" MSG_CLASSIC_PID);
SERIAL_PROTOCOLPAIR(MSG_KP, workKp); SERIAL_PROTOCOLPAIR(MSG_KP, workKp);
SERIAL_PROTOCOLPAIR(MSG_KI, workKi); SERIAL_PROTOCOLPAIR(MSG_KI, workKi);
@ -644,7 +644,7 @@ float Temperature::get_pid_output(const int8_t e) {
#if ENABLED(PIDTEMP) #if ENABLED(PIDTEMP)
#if DISABLED(PID_OPENLOOP) #if DISABLED(PID_OPENLOOP)
pid_error[HOTEND_INDEX] = target_temperature[HOTEND_INDEX] - current_temperature[HOTEND_INDEX]; pid_error[HOTEND_INDEX] = target_temperature[HOTEND_INDEX] - current_temperature[HOTEND_INDEX];
dTerm[HOTEND_INDEX] = PID_K2 * PID_PARAM(Kd, HOTEND_INDEX) * (current_temperature[HOTEND_INDEX] - temp_dState[HOTEND_INDEX]) + PID_K1 * dTerm[HOTEND_INDEX]; dTerm[HOTEND_INDEX] = PID_K2 * PID_PARAM(Kd, HOTEND_INDEX) * (current_temperature[HOTEND_INDEX] - temp_dState[HOTEND_INDEX]) + float(PID_K1) * dTerm[HOTEND_INDEX];
temp_dState[HOTEND_INDEX] = current_temperature[HOTEND_INDEX]; temp_dState[HOTEND_INDEX] = current_temperature[HOTEND_INDEX];
#if HEATER_IDLE_HANDLER #if HEATER_IDLE_HANDLER
if (heater_idle_timeout_exceeded[HOTEND_INDEX]) { if (heater_idle_timeout_exceeded[HOTEND_INDEX]) {
@ -1098,7 +1098,7 @@ void Temperature::updateTemperaturesFromRawValues() {
// Convert raw Filament Width to millimeters // Convert raw Filament Width to millimeters
float Temperature::analog2widthFil() { float Temperature::analog2widthFil() {
return current_raw_filwidth * 5.0 * (1.0 / 16383.0); return current_raw_filwidth * 5.0f * (1.0f / 16383.0f);
} }
/** /**
@ -1111,7 +1111,7 @@ void Temperature::updateTemperaturesFromRawValues() {
*/ */
int8_t Temperature::widthFil_to_size_ratio() { int8_t Temperature::widthFil_to_size_ratio() {
if (ABS(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.0f * filament_width_nominal / filament_width_meas) - 100;
return 0; return 0;
} }

View file

@ -100,14 +100,14 @@ enum ADCSensorState : char {
#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-float(PID_K1))
#define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / TEMP_TIMER_FREQUENCY) #define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / TEMP_TIMER_FREQUENCY)
// Apply the scale factors to the PID values // Apply the scale factors to the PID values
#define scalePID_i(i) ( (i) * PID_dT ) #define scalePID_i(i) ( float(i) * PID_dT )
#define unscalePID_i(i) ( (i) / PID_dT ) #define unscalePID_i(i) ( float(i) / PID_dT )
#define scalePID_d(d) ( (d) / PID_dT ) #define scalePID_d(d) ( float(d) / PID_dT )
#define unscalePID_d(d) ( (d) * PID_dT ) #define unscalePID_d(d) ( float(d) * PID_dT )
#endif #endif
class Temperature { class Temperature {