Просмотр исходного кода

Merge pull request #11178 from ejtagle/misc-fixes

[2.0.x] Use 'float' instead of 'double' maths
Scott Lahteine 6 лет назад
Родитель
Сommit
dde009efdf
Аккаунт пользователя с таким Email не найден
41 измененных файлов: 291 добавлений и 348 удалений
  1. 3
    0
      Marlin/src/HAL/HAL_AVR/HAL.h
  2. 6
    6
      Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp
  3. 0
    5
      Marlin/src/Marlin.h
  4. 21
    20
      Marlin/src/core/macros.h
  5. 2
    2
      Marlin/src/core/utility.h
  6. 1
    1
      Marlin/src/feature/I2CPositionEncoder.cpp
  7. 0
    4
      Marlin/src/feature/I2CPositionEncoder.h
  8. 4
    4
      Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h
  9. 6
    6
      Marlin/src/feature/bedlevel/ubl/ubl.h
  10. 3
    3
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  11. 11
    11
      Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
  12. 2
    2
      Marlin/src/feature/dac/stepper_dac.cpp
  13. 1
    1
      Marlin/src/feature/digipot/digipot_mcp4018.cpp
  14. 1
    1
      Marlin/src/feature/digipot/digipot_mcp4451.cpp
  15. 8
    8
      Marlin/src/gcode/calibrate/G33.cpp
  16. 3
    3
      Marlin/src/gcode/calibrate/M48.cpp
  17. 3
    3
      Marlin/src/gcode/config/M200-M205.cpp
  18. 1
    1
      Marlin/src/gcode/config/M92.cpp
  19. 3
    3
      Marlin/src/gcode/control/M3-M5.cpp
  20. 1
    1
      Marlin/src/gcode/gcode.cpp
  21. 12
    11
      Marlin/src/gcode/motion/G2_G3.cpp
  22. 14
    14
      Marlin/src/gcode/parser.h
  23. 1
    1
      Marlin/src/gcode/temperature/M104_M109.cpp
  24. 2
    2
      Marlin/src/gcode/temperature/M140_M190.cpp
  25. 0
    19
      Marlin/src/inc/Conditionals_post.h
  26. 1
    1
      Marlin/src/lcd/dogm/status_screen_DOGM.h
  27. 64
    64
      Marlin/src/lcd/ultralcd.cpp
  28. 1
    1
      Marlin/src/libs/vector_3.cpp
  29. 6
    6
      Marlin/src/module/configuration_store.cpp
  30. 17
    40
      Marlin/src/module/delta.cpp
  31. 4
    15
      Marlin/src/module/delta.h
  32. 9
    9
      Marlin/src/module/motion.cpp
  33. 10
    10
      Marlin/src/module/motion.h
  34. 30
    30
      Marlin/src/module/planner.cpp
  35. 9
    9
      Marlin/src/module/planner.h
  36. 14
    14
      Marlin/src/module/planner_bezier.cpp
  37. 1
    1
      Marlin/src/module/printcounter.cpp
  38. 3
    3
      Marlin/src/module/printcounter.h
  39. 1
    1
      Marlin/src/module/probe.cpp
  40. 7
    7
      Marlin/src/module/temperature.cpp
  41. 5
    5
      Marlin/src/module/temperature.h

+ 3
- 0
Marlin/src/HAL/HAL_AVR/HAL.h Просмотреть файл

353
 
353
 
354
 #define HAL_SENSITIVE_PINS 0, 1
354
 #define HAL_SENSITIVE_PINS 0, 1
355
 
355
 
356
+// AVR compatibility
357
+#define strtof strtod
358
+
356
 #endif // _HAL_AVR_H_
359
 #endif // _HAL_AVR_H_

+ 6
- 6
Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp Просмотреть файл

297
 void TMC26XStepper::setCurrent(unsigned int current) {
297
 void TMC26XStepper::setCurrent(unsigned int current) {
298
   unsigned char current_scaling = 0;
298
   unsigned char current_scaling = 0;
299
   //calculate the current scaling from the max current setting (in mA)
299
   //calculate the current scaling from the max current setting (in mA)
300
-  double mASetting = (double)current,
301
-         resistor_value = (double)this->resistor;
300
+  float mASetting = (float)current,
301
+         resistor_value = (float)this->resistor;
302
   // remove vsense flag
302
   // remove vsense flag
303
   this->driver_configuration_register_value &= ~(VSENSE);
303
   this->driver_configuration_register_value &= ~(VSENSE);
304
   // Derived from I = (cs + 1) / 32 * (Vsense / Rsense)
304
   // Derived from I = (cs + 1) / 32 * (Vsense / Rsense)
340
 unsigned int TMC26XStepper::getCurrent(void) {
340
 unsigned int TMC26XStepper::getCurrent(void) {
341
   // Calculate the current according to the datasheet to be on the safe side.
341
   // Calculate the current according to the datasheet to be on the safe side.
342
   // This is not the fastest but the most accurate and illustrative way.
342
   // This is not the fastest but the most accurate and illustrative way.
343
-  double result = (double)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN),
344
-         resistor_value = (double)this->resistor,
343
+  float result = (float)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN),
344
+         resistor_value = (float)this->resistor,
345
          voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31;
345
          voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31;
346
   result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
346
   result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
347
   return (unsigned int)result;
347
   return (unsigned int)result;
739
 }
739
 }
740
 
740
 
741
 unsigned int TMC26XStepper::getCurrentCurrent(void) {
741
 unsigned int TMC26XStepper::getCurrentCurrent(void) {
742
-    double result = (double)getCurrentCSReading(),
743
-           resistor_value = (double)this->resistor,
742
+    float result = (float)getCurrentCSReading(),
743
+           resistor_value = (float)this->resistor,
744
            voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31;
744
            voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31;
745
     result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
745
     result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
746
     return (unsigned int)result;
746
     return (unsigned int)result;

+ 0
- 5
Marlin/src/Marlin.h Просмотреть файл

185
   extern bool suspend_auto_report;
185
   extern bool suspend_auto_report;
186
 #endif
186
 #endif
187
 
187
 
188
-#if ENABLED(AUTO_BED_LEVELING_UBL)
189
-  typedef struct { double A, B, D; } linear_fit;
190
-  linear_fit* lsf_linear_fit(double x[], double y[], double z[], const int);
191
-#endif
192
-
193
 // Inactivity shutdown timer
188
 // Inactivity shutdown timer
194
 extern millis_t max_inactive_time, stepper_inactive_time;
189
 extern millis_t max_inactive_time, stepper_inactive_time;
195
 
190
 

+ 21
- 20
Marlin/src/core/macros.h Просмотреть файл

79
 #define CBI32(n,b) (n &= ~_BV32(b))
79
 #define CBI32(n,b) (n &= ~_BV32(b))
80
 
80
 
81
 // Macros for maths shortcuts
81
 // Macros for maths shortcuts
82
-#ifndef M_PI
83
-  #define M_PI 3.14159265358979323846
84
-#endif
85
-#define RADIANS(d) ((d)*M_PI/180.0)
86
-#define DEGREES(r) ((r)*180.0/M_PI)
82
+#undef M_PI
83
+#define M_PI 3.14159265358979323846f
84
+
85
+#define RADIANS(d) ((d)*float(M_PI)/180.0f)
86
+#define DEGREES(r) ((r)*180.0f/float(M_PI))
87
 #define HYPOT2(x,y) (sq(x)+sq(y))
87
 #define HYPOT2(x,y) (sq(x)+sq(y))
88
 
88
 
89
-#define CIRCLE_AREA(R) (M_PI * sq(R))
90
-#define CIRCLE_CIRC(R) (2.0 * M_PI * (R))
89
+#define CIRCLE_AREA(R) (float(M_PI) * sq(float(R)))
90
+#define CIRCLE_CIRC(R) (2 * float(M_PI) * float(R))
91
 
91
 
92
 #define SIGN(a) ((a>0)-(a<0))
92
 #define SIGN(a) ((a>0)-(a<0))
93
 #define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1)))
93
 #define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1)))
200
 #define PENDING(NOW,SOON) ((long)(NOW-(SOON))<0)
200
 #define PENDING(NOW,SOON) ((long)(NOW-(SOON))<0)
201
 #define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON))
201
 #define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON))
202
 
202
 
203
-#define MMM_TO_MMS(MM_M) ((MM_M)/60.0)
204
-#define MMS_TO_MMM(MM_S) ((MM_S)*60.0)
203
+#define MMM_TO_MMS(MM_M) ((MM_M)/60.0f)
204
+#define MMS_TO_MMM(MM_S) ((MM_S)*60.0f)
205
 
205
 
206
 #define NOOP do{} while(0)
206
 #define NOOP do{} while(0)
207
 
207
 
250
 #define MAX4(a, b, c, d)    MAX(MAX3(a, b, c), d)
250
 #define MAX4(a, b, c, d)    MAX(MAX3(a, b, c), d)
251
 #define MAX5(a, b, c, d, e) MAX(MAX4(a, b, c, d), e)
251
 #define MAX5(a, b, c, d, e) MAX(MAX4(a, b, c, d), e)
252
 
252
 
253
-#define UNEAR_ZERO(x) ((x) < 0.000001)
254
-#define NEAR_ZERO(x) WITHIN(x, -0.000001, 0.000001)
253
+#define UNEAR_ZERO(x) ((x) < 0.000001f)
254
+#define NEAR_ZERO(x) WITHIN(x, -0.000001f, 0.000001f)
255
 #define NEAR(x,y) NEAR_ZERO((x)-(y))
255
 #define NEAR(x,y) NEAR_ZERO((x)-(y))
256
 
256
 
257
-#define RECIPROCAL(x) (NEAR_ZERO(x) ? 0.0 : 1.0 / (x))
258
-#define FIXFLOAT(f) (f + (f < 0.0 ? -0.00005 : 0.00005))
257
+#define RECIPROCAL(x) (NEAR_ZERO(x) ? 0 : (1 / float(x)))
258
+#define FIXFLOAT(f) (f + (f < 0 ? -0.00005f : 0.00005f))
259
 
259
 
260
 //
260
 //
261
 // Maths macros that can be overridden by HAL
261
 // Maths macros that can be overridden by HAL
262
 //
262
 //
263
-#define ATAN2(y, x) atan2(y, x)
264
-#define POW(x, y)   pow(x, y)
265
-#define SQRT(x)     sqrt(x)
266
-#define CEIL(x)     ceil(x)
267
-#define FLOOR(x)    floor(x)
268
-#define LROUND(x)   lround(x)
269
-#define FMOD(x, y)  fmod(x, y)
263
+#define ATAN2(y, x) atan2f(y, x)
264
+#define POW(x, y)   powf(x, y)
265
+#define SQRT(x)     sqrtf(x)
266
+#define RSQRT(x)    (1 / sqrtf(x))
267
+#define CEIL(x)     ceilf(x)
268
+#define FLOOR(x)    floorf(x)
269
+#define LROUND(x)   lroundf(x)
270
+#define FMOD(x, y)  fmodf(x, y)
270
 #define HYPOT(x,y)  SQRT(HYPOT2(x,y))
271
 #define HYPOT(x,y)  SQRT(HYPOT2(x,y))
271
 
272
 
272
 #endif //__MACROS_H
273
 #endif //__MACROS_H

+ 2
- 2
Marlin/src/core/utility.h Просмотреть файл

87
   char* ftostr62rj(const float &x);
87
   char* ftostr62rj(const float &x);
88
 
88
 
89
   // Convert float to rj string with 123 or -12 format
89
   // Convert float to rj string with 123 or -12 format
90
-  FORCE_INLINE char* ftostr3(const float &x) { return itostr3(int(x + (x < 0 ? -0.5 : 0.5))); }
90
+  FORCE_INLINE char* ftostr3(const float &x) { return itostr3(int(x + (x < 0 ? -0.5f : 0.5f))); }
91
 
91
 
92
   #if ENABLED(LCD_DECIMAL_SMALL_XY)
92
   #if ENABLED(LCD_DECIMAL_SMALL_XY)
93
     // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format
93
     // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format
94
     char* ftostr4sign(const float &fx);
94
     char* ftostr4sign(const float &fx);
95
   #else
95
   #else
96
     // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format
96
     // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format
97
-    FORCE_INLINE char* ftostr4sign(const float &x) { return itostr4sign(int(x + (x < 0 ? -0.5 : 0.5))); }
97
+    FORCE_INLINE char* ftostr4sign(const float &x) { return itostr4sign(int(x + (x < 0 ? -0.5f : 0.5f))); }
98
   #endif
98
   #endif
99
 
99
 
100
 #endif // ULTRA_LCD
100
 #endif // ULTRA_LCD

+ 1
- 1
Marlin/src/feature/I2CPositionEncoder.cpp Просмотреть файл

181
           if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) {
181
           if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) {
182
             float sumP = 0;
182
             float sumP = 0;
183
             LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i];
183
             LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i];
184
-            const int32_t errorP = int32_t(sumP * (1.0 / (I2CPE_ERR_PRST_ARRAY_SIZE)));
184
+            const int32_t errorP = int32_t(sumP * (1.0f / (I2CPE_ERR_PRST_ARRAY_SIZE)));
185
             SERIAL_ECHO(axis_codes[encoderAxis]);
185
             SERIAL_ECHO(axis_codes[encoderAxis]);
186
             SERIAL_ECHOPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis]);
186
             SERIAL_ECHOPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis]);
187
             SERIAL_ECHOLNPGM("mm; correcting!");
187
             SERIAL_ECHOLNPGM("mm; correcting!");

+ 0
- 4
Marlin/src/feature/I2CPositionEncoder.h Просмотреть файл

133
               nextErrorCountTime  = 0,
133
               nextErrorCountTime  = 0,
134
               lastErrorTime;
134
               lastErrorTime;
135
 
135
 
136
-    //double        positionMm; //calculate
137
-
138
     #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE)
136
     #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE)
139
       uint8_t errIdx = 0, errPrstIdx = 0;
137
       uint8_t errIdx = 0, errPrstIdx = 0;
140
       int err[I2CPE_ERR_ARRAY_SIZE] = { 0 },
138
       int err[I2CPE_ERR_ARRAY_SIZE] = { 0 },
141
           errPrst[I2CPE_ERR_PRST_ARRAY_SIZE] = { 0 };
139
           errPrst[I2CPE_ERR_PRST_ARRAY_SIZE] = { 0 };
142
     #endif
140
     #endif
143
 
141
 
144
-    //float        positionMm; //calculate
145
-
146
   public:
142
   public:
147
     void init(const uint8_t address, const AxisEnum axis);
143
     void init(const uint8_t address, const AxisEnum axis);
148
     void reset();
144
     void reset();

+ 4
- 4
Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h Просмотреть файл

72
   }
72
   }
73
 
73
 
74
   static int8_t cell_index_x(const float &x) {
74
   static int8_t cell_index_x(const float &x) {
75
-    int8_t cx = (x - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST));
75
+    int8_t cx = (x - (MESH_MIN_X)) * (1.0f / (MESH_X_DIST));
76
     return constrain(cx, 0, (GRID_MAX_POINTS_X) - 2);
76
     return constrain(cx, 0, (GRID_MAX_POINTS_X) - 2);
77
   }
77
   }
78
 
78
 
79
   static int8_t cell_index_y(const float &y) {
79
   static int8_t cell_index_y(const float &y) {
80
-    int8_t cy = (y - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST));
80
+    int8_t cy = (y - (MESH_MIN_Y)) * (1.0f / (MESH_Y_DIST));
81
     return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 2);
81
     return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 2);
82
   }
82
   }
83
 
83
 
84
   static int8_t probe_index_x(const float &x) {
84
   static int8_t probe_index_x(const float &x) {
85
-    int8_t px = (x - (MESH_MIN_X) + 0.5 * (MESH_X_DIST)) * (1.0 / (MESH_X_DIST));
85
+    int8_t px = (x - (MESH_MIN_X) + 0.5 * (MESH_X_DIST)) * (1.0f / (MESH_X_DIST));
86
     return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1;
86
     return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1;
87
   }
87
   }
88
 
88
 
89
   static int8_t probe_index_y(const float &y) {
89
   static int8_t probe_index_y(const float &y) {
90
-    int8_t py = (y - (MESH_MIN_Y) + 0.5 * (MESH_Y_DIST)) * (1.0 / (MESH_Y_DIST));
90
+    int8_t py = (y - (MESH_MIN_Y) + 0.5 * (MESH_Y_DIST)) * (1.0f / (MESH_Y_DIST));
91
     return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1;
91
     return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1;
92
   }
92
   }
93
 
93
 

+ 6
- 6
Marlin/src/feature/bedlevel/ubl/ubl.h Просмотреть файл

168
     FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; }
168
     FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; }
169
 
169
 
170
     static int8_t get_cell_index_x(const float &x) {
170
     static int8_t get_cell_index_x(const float &x) {
171
-      const int8_t cx = (x - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST));
171
+      const int8_t cx = (x - (MESH_MIN_X)) * (1.0f / (MESH_X_DIST));
172
       return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1);   // -1 is appropriate if we want all movement to the X_MAX
172
       return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1);   // -1 is appropriate if we want all movement to the X_MAX
173
     }                                                     // position. But with this defined this way, it is possible
173
     }                                                     // position. But with this defined this way, it is possible
174
                                                           // to extrapolate off of this point even further out. Probably
174
                                                           // to extrapolate off of this point even further out. Probably
175
                                                           // that is OK because something else should be keeping that from
175
                                                           // that is OK because something else should be keeping that from
176
                                                           // happening and should not be worried about at this level.
176
                                                           // happening and should not be worried about at this level.
177
     static int8_t get_cell_index_y(const float &y) {
177
     static int8_t get_cell_index_y(const float &y) {
178
-      const int8_t cy = (y - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST));
178
+      const int8_t cy = (y - (MESH_MIN_Y)) * (1.0f / (MESH_Y_DIST));
179
       return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1);   // -1 is appropriate if we want all movement to the Y_MAX
179
       return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1);   // -1 is appropriate if we want all movement to the Y_MAX
180
     }                                                     // position. But with this defined this way, it is possible
180
     }                                                     // position. But with this defined this way, it is possible
181
                                                           // to extrapolate off of this point even further out. Probably
181
                                                           // to extrapolate off of this point even further out. Probably
183
                                                           // happening and should not be worried about at this level.
183
                                                           // happening and should not be worried about at this level.
184
 
184
 
185
     static int8_t find_closest_x_index(const float &x) {
185
     static int8_t find_closest_x_index(const float &x) {
186
-      const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * (1.0 / (MESH_X_DIST));
186
+      const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * (1.0f / (MESH_X_DIST));
187
       return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1;
187
       return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1;
188
     }
188
     }
189
 
189
 
190
     static int8_t find_closest_y_index(const float &y) {
190
     static int8_t find_closest_y_index(const float &y) {
191
-      const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * (1.0 / (MESH_Y_DIST));
191
+      const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * (1.0f / (MESH_Y_DIST));
192
       return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1;
192
       return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1;
193
     }
193
     }
194
 
194
 
238
         );
238
         );
239
       }
239
       }
240
 
240
 
241
-      const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * (1.0 / (MESH_X_DIST)),
241
+      const float xratio = (rx0 - mesh_index_to_xpos(x1_i)) * (1.0f / (MESH_X_DIST)),
242
                   z1 = z_values[x1_i][yi];
242
                   z1 = z_values[x1_i][yi];
243
 
243
 
244
       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
244
       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
         );
272
         );
273
       }
273
       }
274
 
274
 
275
-      const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * (1.0 / (MESH_Y_DIST)),
275
+      const float yratio = (ry0 - mesh_index_to_ypos(y1_i)) * (1.0f / (MESH_Y_DIST)),
276
                   z1 = z_values[xi][y1_i];
276
                   z1 = z_values[xi][y1_i];
277
 
277
 
278
       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
278
       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

+ 3
- 3
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp Просмотреть файл

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

+ 11
- 11
Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp Просмотреть файл

102
       FINAL_MOVE:
102
       FINAL_MOVE:
103
 
103
 
104
       // The distance is always MESH_X_DIST so multiply by the constant reciprocal.
104
       // The distance is always MESH_X_DIST so multiply by the constant reciprocal.
105
-      const float xratio = (end[X_AXIS] - mesh_index_to_xpos(cell_dest_xi)) * (1.0 / (MESH_X_DIST));
105
+      const float xratio = (end[X_AXIS] - mesh_index_to_xpos(cell_dest_xi)) * (1.0f / (MESH_X_DIST));
106
 
106
 
107
       float z1 = z_values[cell_dest_xi    ][cell_dest_yi    ] + xratio *
107
       float z1 = z_values[cell_dest_xi    ][cell_dest_yi    ] + xratio *
108
                 (z_values[cell_dest_xi + 1][cell_dest_yi    ] - z_values[cell_dest_xi][cell_dest_yi    ]),
108
                 (z_values[cell_dest_xi + 1][cell_dest_yi    ] - z_values[cell_dest_xi][cell_dest_yi    ]),
112
       if (cell_dest_xi >= GRID_MAX_POINTS_X - 1) z1 = z2 = 0.0;
112
       if (cell_dest_xi >= GRID_MAX_POINTS_X - 1) z1 = z2 = 0.0;
113
 
113
 
114
       // X cell-fraction done. Interpolate the two Z offsets with the Y fraction for the final Z offset.
114
       // X cell-fraction done. Interpolate the two Z offsets with the Y fraction for the final Z offset.
115
-      const float yratio = (end[Y_AXIS] - mesh_index_to_ypos(cell_dest_yi)) * (1.0 / (MESH_Y_DIST)),
115
+      const float yratio = (end[Y_AXIS] - mesh_index_to_ypos(cell_dest_yi)) * (1.0f / (MESH_Y_DIST)),
116
                   z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0;
116
                   z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0;
117
 
117
 
118
       // Undefined parts of the Mesh in z_values[][] are NAN.
118
       // Undefined parts of the Mesh in z_values[][] are NAN.
440
     #if IS_KINEMATIC
440
     #if IS_KINEMATIC
441
       const float seconds = cartesian_xy_mm / feedrate;                                  // seconds to move xy distance at requested rate
441
       const float seconds = cartesian_xy_mm / feedrate;                                  // seconds to move xy distance at requested rate
442
       uint16_t segments = lroundf(delta_segments_per_second * seconds),                  // preferred number of segments for distance @ feedrate
442
       uint16_t segments = lroundf(delta_segments_per_second * seconds),                  // preferred number of segments for distance @ feedrate
443
-               seglimit = lroundf(cartesian_xy_mm * (1.0 / (DELTA_SEGMENT_MIN_LENGTH))); // number of segments at minimum segment length
443
+               seglimit = lroundf(cartesian_xy_mm * (1.0f / (DELTA_SEGMENT_MIN_LENGTH))); // number of segments at minimum segment length
444
       NOMORE(segments, seglimit);                                                        // limit to minimum segment length (fewer segments)
444
       NOMORE(segments, seglimit);                                                        // limit to minimum segment length (fewer segments)
445
     #else
445
     #else
446
-      uint16_t segments = lroundf(cartesian_xy_mm * (1.0 / (DELTA_SEGMENT_MIN_LENGTH))); // cartesian fixed segment length
446
+      uint16_t segments = lroundf(cartesian_xy_mm * (1.0f / (DELTA_SEGMENT_MIN_LENGTH))); // cartesian fixed segment length
447
     #endif
447
     #endif
448
 
448
 
449
     NOLESS(segments, 1U);                        // must have at least one segment
449
     NOLESS(segments, 1U);                        // must have at least one segment
450
-    const float inv_segments = 1.0 / segments;  // divide once, multiply thereafter
450
+    const float inv_segments = 1.0f / segments;  // divide once, multiply thereafter
451
 
451
 
452
     #if IS_SCARA // scale the feed rate from mm/s to degrees/s
452
     #if IS_SCARA // scale the feed rate from mm/s to degrees/s
453
       scara_feed_factor = cartesian_xy_mm * inv_segments * feedrate;
453
       scara_feed_factor = cartesian_xy_mm * inv_segments * feedrate;
500
       // in top of loop and again re-find same adjacent cell and use it, just less efficient
500
       // in top of loop and again re-find same adjacent cell and use it, just less efficient
501
       // for mesh inset area.
501
       // for mesh inset area.
502
 
502
 
503
-      int8_t cell_xi = (raw[X_AXIS] - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST)),
504
-             cell_yi = (raw[Y_AXIS] - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST));
503
+      int8_t cell_xi = (raw[X_AXIS] - (MESH_MIN_X)) * (1.0f / (MESH_X_DIST)),
504
+             cell_yi = (raw[Y_AXIS] - (MESH_MIN_Y)) * (1.0f / (MESH_Y_DIST));
505
 
505
 
506
       cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1);
506
       cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1);
507
       cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1);
507
       cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1);
522
       float cx = raw[X_AXIS] - x0,   // cell-relative x and y
522
       float cx = raw[X_AXIS] - x0,   // cell-relative x and y
523
             cy = raw[Y_AXIS] - y0;
523
             cy = raw[Y_AXIS] - y0;
524
 
524
 
525
-      const float z_xmy0 = (z_x1y0 - z_x0y0) * (1.0 / (MESH_X_DIST)),   // z slope per x along y0 (lower left to lower right)
526
-                  z_xmy1 = (z_x1y1 - z_x0y1) * (1.0 / (MESH_X_DIST));   // z slope per x along y1 (upper left to upper right)
525
+      const float z_xmy0 = (z_x1y0 - z_x0y0) * (1.0f / (MESH_X_DIST)),   // z slope per x along y0 (lower left to lower right)
526
+                  z_xmy1 = (z_x1y1 - z_x0y1) * (1.0f / (MESH_X_DIST));   // z slope per x along y1 (upper left to upper right)
527
 
527
 
528
             float z_cxy0 = z_x0y0 + z_xmy0 * cx;            // z height along y0 at cx (changes for each cx in cell)
528
             float z_cxy0 = z_x0y0 + z_xmy0 * cx;            // z height along y0 at cx (changes for each cx in cell)
529
 
529
 
530
       const float z_cxy1 = z_x0y1 + z_xmy1 * cx,            // z height along y1 at cx
530
       const float z_cxy1 = z_x0y1 + z_xmy1 * cx,            // z height along y1 at cx
531
                   z_cxyd = z_cxy1 - z_cxy0;                 // z height difference along cx from y0 to y1
531
                   z_cxyd = z_cxy1 - z_cxy0;                 // z height difference along cx from y0 to y1
532
 
532
 
533
-            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)
533
+            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)
534
 
534
 
535
       //    float z_cxcy = z_cxy0 + z_cxym * cy;            // interpolated mesh z height along cx at cy (do inside the segment loop)
535
       //    float z_cxcy = z_cxy0 + z_cxym * cy;            // interpolated mesh z height along cx at cy (do inside the segment loop)
536
 
536
 
539
       // each change by a constant for fixed segment lengths.
539
       // each change by a constant for fixed segment lengths.
540
 
540
 
541
       const float z_sxy0 = z_xmy0 * diff[X_AXIS],                                     // per-segment adjustment to z_cxy0
541
       const float z_sxy0 = z_xmy0 * diff[X_AXIS],                                     // per-segment adjustment to z_cxy0
542
-                  z_sxym = (z_xmy1 - z_xmy0) * (1.0 / (MESH_Y_DIST)) * diff[X_AXIS];  // per-segment adjustment to z_cxym
542
+                  z_sxym = (z_xmy1 - z_xmy0) * (1.0f / (MESH_Y_DIST)) * diff[X_AXIS];  // per-segment adjustment to z_cxym
543
 
543
 
544
       for (;;) {  // for all segments within this mesh cell
544
       for (;;) {  // for all segments within this mesh cell
545
 
545
 

+ 2
- 2
Marlin/src/feature/dac/stepper_dac.cpp Просмотреть файл

91
   mcp4728_simpleCommand(UPDATE);
91
   mcp4728_simpleCommand(UPDATE);
92
 }
92
 }
93
 
93
 
94
-static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * (1.0 / (DAC_STEPPER_MAX)); }
95
-static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * (1.0 / (DAC_STEPPER_SENSE)); }
94
+static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * (1.0f / (DAC_STEPPER_MAX)); }
95
+static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * (1.0f / (DAC_STEPPER_SENSE)); }
96
 
96
 
97
 uint8_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); }
97
 uint8_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); }
98
 void dac_current_set_percents(const uint8_t pct[XYZE]) {
98
 void dac_current_set_percents(const uint8_t pct[XYZE]) {

+ 1
- 1
Marlin/src/feature/digipot/digipot_mcp4018.cpp Просмотреть файл

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

+ 1
- 1
Marlin/src/feature/digipot/digipot_mcp4451.cpp Просмотреть файл

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

+ 8
- 8
Marlin/src/gcode/calibrate/G33.cpp Просмотреть файл

185
         S2 += sq(z_pt[rad]);
185
         S2 += sq(z_pt[rad]);
186
         N++;
186
         N++;
187
       }
187
       }
188
-      return round(SQRT(S2 / N) * 1000.0) / 1000.0 + 0.00001;
188
+      return LROUND(SQRT(S2 / N) * 1000.0) / 1000.0 + 0.00001;
189
     }
189
     }
190
   }
190
   }
191
   return 0.00001;
191
   return 0.00001;
277
           const float z_temp = calibration_probe(cos(a) * r, sin(a) * r, stow_after_each, set_up);
277
           const float z_temp = calibration_probe(cos(a) * r, sin(a) * r, stow_after_each, set_up);
278
           if (isnan(z_temp)) return false;
278
           if (isnan(z_temp)) return false;
279
           // split probe point to neighbouring calibration points
279
           // split probe point to neighbouring calibration points
280
-          z_pt[uint8_t(round(rad - interpol + NPP - 1)) % NPP + 1] += z_temp * sq(cos(RADIANS(interpol * 90)));
281
-          z_pt[uint8_t(round(rad - interpol))           % NPP + 1] += z_temp * sq(sin(RADIANS(interpol * 90)));
280
+          z_pt[uint8_t(LROUND(rad - interpol + NPP - 1)) % NPP + 1] += z_temp * sq(cos(RADIANS(interpol * 90)));
281
+          z_pt[uint8_t(LROUND(rad - interpol))           % NPP + 1] += z_temp * sq(sin(RADIANS(interpol * 90)));
282
         }
282
         }
283
         zig_zag = !zig_zag;
283
         zig_zag = !zig_zag;
284
       }
284
       }
359
   float h_fac = 0.0;
359
   float h_fac = 0.0;
360
 
360
 
361
   h_fac = r_quot / (2.0 / 3.0);
361
   h_fac = r_quot / (2.0 / 3.0);
362
-  h_fac = 1.0 / h_fac; // (2/3)/CR
362
+  h_fac = 1.0f / h_fac; // (2/3)/CR
363
   return h_fac;
363
   return h_fac;
364
 }
364
 }
365
 
365
 
680
         char mess[21];
680
         char mess[21];
681
         strcpy_P(mess, PSTR("Calibration sd:"));
681
         strcpy_P(mess, PSTR("Calibration sd:"));
682
         if (zero_std_dev_min < 1)
682
         if (zero_std_dev_min < 1)
683
-          sprintf_P(&mess[15], PSTR("0.%03i"), (int)round(zero_std_dev_min * 1000.0));
683
+          sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev_min * 1000.0));
684
         else
684
         else
685
-          sprintf_P(&mess[15], PSTR("%03i.x"), (int)round(zero_std_dev_min));
685
+          sprintf_P(&mess[15], PSTR("%03i.x"), (int)LROUND(zero_std_dev_min));
686
         lcd_setstatus(mess);
686
         lcd_setstatus(mess);
687
         print_calibration_settings(_endstop_results, _angle_results);
687
         print_calibration_settings(_endstop_results, _angle_results);
688
         serialprintPGM(save_message);
688
         serialprintPGM(save_message);
716
       strcpy_P(mess, enddryrun);
716
       strcpy_P(mess, enddryrun);
717
       strcpy_P(&mess[11], PSTR(" sd:"));
717
       strcpy_P(&mess[11], PSTR(" sd:"));
718
       if (zero_std_dev < 1)
718
       if (zero_std_dev < 1)
719
-        sprintf_P(&mess[15], PSTR("0.%03i"), (int)round(zero_std_dev * 1000.0));
719
+        sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev * 1000.0));
720
       else
720
       else
721
-        sprintf_P(&mess[15], PSTR("%03i.x"), (int)round(zero_std_dev));
721
+        sprintf_P(&mess[15], PSTR("%03i.x"), (int)LROUND(zero_std_dev));
722
       lcd_setstatus(mess);
722
       lcd_setstatus(mess);
723
     }
723
     }
724
     ac_home();
724
     ac_home();

+ 3
- 3
Marlin/src/gcode/calibrate/M48.cpp Просмотреть файл

111
 
111
 
112
   setup_for_endstop_or_probe_move();
112
   setup_for_endstop_or_probe_move();
113
 
113
 
114
-  double mean = 0.0, sigma = 0.0, min = 99999.9, max = -99999.9, sample_set[n_samples];
114
+  float mean = 0.0, sigma = 0.0, min = 99999.9, max = -99999.9, sample_set[n_samples];
115
 
115
 
116
   // Move to the first point, deploy, and probe
116
   // Move to the first point, deploy, and probe
117
   const float t = probe_pt(X_probe_location, Y_probe_location, raise_after, verbose_level);
117
   const float t = probe_pt(X_probe_location, Y_probe_location, raise_after, verbose_level);
142
         }
142
         }
143
 
143
 
144
         for (uint8_t l = 0; l < n_legs - 1; l++) {
144
         for (uint8_t l = 0; l < n_legs - 1; l++) {
145
-          double delta_angle;
145
+          float delta_angle;
146
 
146
 
147
           if (schizoid_flag)
147
           if (schizoid_flag)
148
             // The points of a 5 point star are 72 degrees apart.  We need to
148
             // The points of a 5 point star are 72 degrees apart.  We need to
199
       /**
199
       /**
200
        * Get the current mean for the data points we have so far
200
        * Get the current mean for the data points we have so far
201
        */
201
        */
202
-      double sum = 0.0;
202
+      float sum = 0.0;
203
       for (uint8_t j = 0; j <= n; j++) sum += sample_set[j];
203
       for (uint8_t j = 0; j <= n; j++) sum += sample_set[j];
204
       mean = sum / (n + 1);
204
       mean = sum / (n + 1);
205
 
205
 

+ 3
- 3
Marlin/src/gcode/config/M200-M205.cpp Просмотреть файл

40
       // setting any extruder filament size disables volumetric on the assumption that
40
       // setting any extruder filament size disables volumetric on the assumption that
41
       // slicers either generate in extruder values as cubic mm or as as filament feeds
41
       // slicers either generate in extruder values as cubic mm or as as filament feeds
42
       // for all extruders
42
       // for all extruders
43
-      if ( (parser.volumetric_enabled = (parser.value_linear_units() != 0.0)) )
43
+      if ( (parser.volumetric_enabled = (parser.value_linear_units() != 0)) )
44
         planner.set_filament_size(target_extruder, parser.value_linear_units());
44
         planner.set_filament_size(target_extruder, parser.value_linear_units());
45
     }
45
     }
46
     planner.calculate_volumetric_multipliers();
46
     planner.calculate_volumetric_multipliers();
134
   #if ENABLED(JUNCTION_DEVIATION)
134
   #if ENABLED(JUNCTION_DEVIATION)
135
     if (parser.seen('J')) {
135
     if (parser.seen('J')) {
136
       const float junc_dev = parser.value_linear_units();
136
       const float junc_dev = parser.value_linear_units();
137
-      if (WITHIN(junc_dev, 0.01, 0.3)) {
137
+      if (WITHIN(junc_dev, 0.01f, 0.3f)) {
138
         planner.junction_deviation_mm = junc_dev;
138
         planner.junction_deviation_mm = junc_dev;
139
         planner.recalculate_max_e_jerk();
139
         planner.recalculate_max_e_jerk();
140
       }
140
       }
149
     if (parser.seen('Z')) {
149
     if (parser.seen('Z')) {
150
       planner.max_jerk[Z_AXIS] = parser.value_linear_units();
150
       planner.max_jerk[Z_AXIS] = parser.value_linear_units();
151
       #if HAS_MESH
151
       #if HAS_MESH
152
-        if (planner.max_jerk[Z_AXIS] <= 0.1)
152
+        if (planner.max_jerk[Z_AXIS] <= 0.1f)
153
           SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses.");
153
           SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses.");
154
       #endif
154
       #endif
155
     }
155
     }

+ 1
- 1
Marlin/src/gcode/config/M92.cpp Просмотреть файл

37
     if (parser.seen(axis_codes[i])) {
37
     if (parser.seen(axis_codes[i])) {
38
       if (i == E_AXIS) {
38
       if (i == E_AXIS) {
39
         const float value = parser.value_per_axis_unit((AxisEnum)(E_AXIS + TARGET_EXTRUDER));
39
         const float value = parser.value_per_axis_unit((AxisEnum)(E_AXIS + TARGET_EXTRUDER));
40
-        if (value < 20.0) {
40
+        if (value < 20) {
41
           float factor = planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] / value; // increase e constants if M92 E14 is given for netfab.
41
           float factor = planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] / value; // increase e constants if M92 E14 is given for netfab.
42
           #if DISABLED(JUNCTION_DEVIATION)
42
           #if DISABLED(JUNCTION_DEVIATION)
43
             planner.max_jerk[E_AXIS] *= factor;
43
             planner.max_jerk[E_AXIS] *= factor;

+ 3
- 3
Marlin/src/gcode/control/M3-M5.cpp Просмотреть файл

107
         delay_for_power_down();
107
         delay_for_power_down();
108
       }
108
       }
109
       else {
109
       else {
110
-        int16_t ocr_val = (spindle_laser_power - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE));  // convert RPM to PWM duty cycle
110
+        int16_t ocr_val = (spindle_laser_power - (SPEED_POWER_INTERCEPT)) * (1.0f / (SPEED_POWER_SLOPE));  // convert RPM to PWM duty cycle
111
         NOMORE(ocr_val, 255);                                                                             // limit to max the Atmel PWM will support
111
         NOMORE(ocr_val, 255);                                                                             // limit to max the Atmel PWM will support
112
         if (spindle_laser_power <= SPEED_POWER_MIN)
112
         if (spindle_laser_power <= SPEED_POWER_MIN)
113
-          ocr_val = (SPEED_POWER_MIN - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE));            // minimum setting
113
+          ocr_val = (SPEED_POWER_MIN - (SPEED_POWER_INTERCEPT)) * (1.0f / (SPEED_POWER_SLOPE));            // minimum setting
114
         if (spindle_laser_power >= SPEED_POWER_MAX)
114
         if (spindle_laser_power >= SPEED_POWER_MAX)
115
-          ocr_val = (SPEED_POWER_MAX - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE));            // limit to max RPM
115
+          ocr_val = (SPEED_POWER_MAX - (SPEED_POWER_INTERCEPT)) * (1.0f / (SPEED_POWER_SLOPE));            // limit to max RPM
116
         if (SPINDLE_LASER_PWM_INVERT) ocr_val = 255 - ocr_val;
116
         if (SPINDLE_LASER_PWM_INVERT) ocr_val = 255 - ocr_val;
117
         WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT);                                     // turn spindle on (active low)
117
         WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT);                                     // turn spindle on (active low)
118
         analogWrite(SPINDLE_LASER_PWM_PIN, ocr_val & 0xFF);                                               // only write low byte
118
         analogWrite(SPINDLE_LASER_PWM_PIN, ocr_val & 0xFF);                                               // only write low byte

+ 1
- 1
Marlin/src/gcode/gcode.cpp Просмотреть файл

103
       destination[i] = current_position[i];
103
       destination[i] = current_position[i];
104
   }
104
   }
105
 
105
 
106
-  if (parser.linearval('F') > 0.0)
106
+  if (parser.linearval('F') > 0)
107
     feedrate_mm_s = MMM_TO_MMS(parser.value_feedrate());
107
     feedrate_mm_s = MMM_TO_MMS(parser.value_feedrate());
108
 
108
 
109
   #if ENABLED(PRINTCOUNTER)
109
   #if ENABLED(PRINTCOUNTER)

+ 12
- 11
Marlin/src/gcode/motion/G2_G3.cpp Просмотреть файл

92
 
92
 
93
   const float flat_mm = radius * angular_travel,
93
   const float flat_mm = radius * angular_travel,
94
               mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm);
94
               mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm);
95
-  if (mm_of_travel < 0.001) return;
95
+  if (mm_of_travel < 0.001f) return;
96
 
96
 
97
   uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT));
97
   uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT));
98
   if (segments == 0) segments = 1;
98
   if (segments == 0) segments = 1;
129
               linear_per_segment = linear_travel / segments,
129
               linear_per_segment = linear_travel / segments,
130
               extruder_per_segment = extruder_travel / segments,
130
               extruder_per_segment = extruder_travel / segments,
131
               sin_T = theta_per_segment,
131
               sin_T = theta_per_segment,
132
-              cos_T = 1 - 0.5 * sq(theta_per_segment); // Small angle approximation
132
+              cos_T = 1 - 0.5f * sq(theta_per_segment); // Small angle approximation
133
 
133
 
134
   // Initialize the linear axis
134
   // Initialize the linear axis
135
   raw[l_axis] = current_position[l_axis];
135
   raw[l_axis] = current_position[l_axis];
143
 
143
 
144
   #if HAS_FEEDRATE_SCALING
144
   #if HAS_FEEDRATE_SCALING
145
     // SCARA needs to scale the feed rate from mm/s to degrees/s
145
     // SCARA needs to scale the feed rate from mm/s to degrees/s
146
-    const float inv_segment_length = 1.0 / (MM_PER_ARC_SEGMENT),
146
+    const float inv_segment_length = 1.0f / float(MM_PER_ARC_SEGMENT),
147
                 inverse_secs = inv_segment_length * fr_mm_s;
147
                 inverse_secs = inv_segment_length * fr_mm_s;
148
     float oldA = planner.position_float[A_AXIS],
148
     float oldA = planner.position_float[A_AXIS],
149
           oldB = planner.position_float[B_AXIS]
149
           oldB = planner.position_float[B_AXIS]
289
       relative_mode = relative_mode_backup;
289
       relative_mode = relative_mode_backup;
290
     #endif
290
     #endif
291
 
291
 
292
-    float arc_offset[2] = { 0.0, 0.0 };
292
+    float arc_offset[2] = { 0, 0 };
293
     if (parser.seenval('R')) {
293
     if (parser.seenval('R')) {
294
       const float r = parser.value_linear_units(),
294
       const float r = parser.value_linear_units(),
295
                   p1 = current_position[X_AXIS], q1 = current_position[Y_AXIS],
295
                   p1 = current_position[X_AXIS], q1 = current_position[Y_AXIS],
296
                   p2 = destination[X_AXIS], q2 = destination[Y_AXIS];
296
                   p2 = destination[X_AXIS], q2 = destination[Y_AXIS];
297
       if (r && (p2 != p1 || q2 != q1)) {
297
       if (r && (p2 != p1 || q2 != q1)) {
298
-        const float e = clockwise ^ (r < 0) ? -1 : 1,           // clockwise -1/1, counterclockwise 1/-1
299
-                    dx = p2 - p1, dy = q2 - q1,                 // X and Y differences
300
-                    d = HYPOT(dx, dy),                          // Linear distance between the points
301
-                    h = SQRT(sq(r) - sq(d * 0.5)),              // Distance to the arc pivot-point
302
-                    mx = (p1 + p2) * 0.5, my = (q1 + q2) * 0.5, // Point between the two points
303
-                    sx = -dy / d, sy = dx / d,                  // Slope of the perpendicular bisector
304
-                    cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc
298
+        const float e = clockwise ^ (r < 0) ? -1 : 1,            // clockwise -1/1, counterclockwise 1/-1
299
+                    dx = p2 - p1, dy = q2 - q1,                  // X and Y differences
300
+                    d = HYPOT(dx, dy),                           // Linear distance between the points
301
+                    dinv = 1/d,                                  // Inverse of d
302
+                    h = SQRT(sq(r) - sq(d * 0.5f)),              // Distance to the arc pivot-point
303
+                    mx = (p1 + p2) * 0.5f, my = (q1 + q2) * 0.5f,// Point between the two points
304
+                    sx = -dy * dinv, sy = dx * dinv,             // Slope of the perpendicular bisector
305
+                    cx = mx + e * h * sx, cy = my + e * h * sy;  // Pivot-point of the arc
305
         arc_offset[0] = cx - p1;
306
         arc_offset[0] = cx - p1;
306
         arc_offset[1] = cy - q1;
307
         arc_offset[1] = cy - q1;
307
       }
308
       }

+ 14
- 14
Marlin/src/gcode/parser.h Просмотреть файл

186
         if (c == '\0' || c == ' ') break;
186
         if (c == '\0' || c == ' ') break;
187
         if (c == 'E' || c == 'e') {
187
         if (c == 'E' || c == 'e') {
188
           *e = '\0';
188
           *e = '\0';
189
-          const float ret = strtod(value_ptr, NULL);
189
+          const float ret = strtof(value_ptr, NULL);
190
           *e = c;
190
           *e = c;
191
           return ret;
191
           return ret;
192
         }
192
         }
193
         ++e;
193
         ++e;
194
       }
194
       }
195
-      return strtod(value_ptr, NULL);
195
+      return strtof(value_ptr, NULL);
196
     }
196
     }
197
-    return 0.0;
197
+    return 0;
198
   }
198
   }
199
 
199
 
200
   // Code value as a long or ulong
200
   // Code value as a long or ulong
203
 
203
 
204
   // Code value for use as time
204
   // Code value for use as time
205
   FORCE_INLINE static millis_t value_millis() { return value_ulong(); }
205
   FORCE_INLINE static millis_t value_millis() { return value_ulong(); }
206
-  FORCE_INLINE static millis_t value_millis_from_seconds() { return value_float() * 1000UL; }
206
+  FORCE_INLINE static millis_t value_millis_from_seconds() { return (millis_t)(value_float() * 1000); }
207
 
207
 
208
   // Reduce to fewer bits
208
   // Reduce to fewer bits
209
   FORCE_INLINE static int16_t value_int() { return (int16_t)value_long(); }
209
   FORCE_INLINE static int16_t value_int() { return (int16_t)value_long(); }
220
     inline static void set_input_linear_units(const LinearUnit units) {
220
     inline static void set_input_linear_units(const LinearUnit units) {
221
       switch (units) {
221
       switch (units) {
222
         case LINEARUNIT_INCH:
222
         case LINEARUNIT_INCH:
223
-          linear_unit_factor = 25.4;
223
+          linear_unit_factor = 25.4f;
224
           break;
224
           break;
225
         case LINEARUNIT_MM:
225
         case LINEARUNIT_MM:
226
         default:
226
         default:
227
-          linear_unit_factor = 1.0;
227
+          linear_unit_factor = 1;
228
           break;
228
           break;
229
       }
229
       }
230
-      volumetric_unit_factor = POW(linear_unit_factor, 3.0);
230
+      volumetric_unit_factor = POW(linear_unit_factor, 3);
231
     }
231
     }
232
 
232
 
233
     inline static float axis_unit_factor(const AxisEnum axis) {
233
     inline static float axis_unit_factor(const AxisEnum axis) {
261
       inline static float to_temp_units(const float &f) {
261
       inline static float to_temp_units(const float &f) {
262
         switch (input_temp_units) {
262
         switch (input_temp_units) {
263
           case TEMPUNIT_F:
263
           case TEMPUNIT_F:
264
-            return f * 0.5555555556 + 32.0;
264
+            return f * 0.5555555556f + 32;
265
           case TEMPUNIT_K:
265
           case TEMPUNIT_K:
266
-            return f + 273.15;
266
+            return f + 273.15f;
267
           case TEMPUNIT_C:
267
           case TEMPUNIT_C:
268
           default:
268
           default:
269
             return f;
269
             return f;
276
       const float f = value_float();
276
       const float f = value_float();
277
       switch (input_temp_units) {
277
       switch (input_temp_units) {
278
         case TEMPUNIT_F:
278
         case TEMPUNIT_F:
279
-          return (f - 32.0) * 0.5555555556;
279
+          return (f - 32) * 0.5555555556f;
280
         case TEMPUNIT_K:
280
         case TEMPUNIT_K:
281
-          return f - 273.15;
281
+          return f - 273.15f;
282
         case TEMPUNIT_C:
282
         case TEMPUNIT_C:
283
         default:
283
         default:
284
           return f;
284
           return f;
288
     inline static float value_celsius_diff() {
288
     inline static float value_celsius_diff() {
289
       switch (input_temp_units) {
289
       switch (input_temp_units) {
290
         case TEMPUNIT_F:
290
         case TEMPUNIT_F:
291
-          return value_float() * 0.5555555556;
291
+          return value_float() * 0.5555555556f;
292
         case TEMPUNIT_C:
292
         case TEMPUNIT_C:
293
         case TEMPUNIT_K:
293
         case TEMPUNIT_K:
294
         default:
294
         default:
315
   FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort()       : dval; }
315
   FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort()       : dval; }
316
   FORCE_INLINE static int32_t  longval(const char c, const int32_t dval=0)    { return seenval(c) ? value_long()         : dval; }
316
   FORCE_INLINE static int32_t  longval(const char c, const int32_t dval=0)    { return seenval(c) ? value_long()         : dval; }
317
   FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0)  { return seenval(c) ? value_ulong()        : dval; }
317
   FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0)  { return seenval(c) ? value_ulong()        : dval; }
318
-  FORCE_INLINE static float    linearval(const char c, const float dval=0.0)  { return seenval(c) ? value_linear_units() : dval; }
319
-  FORCE_INLINE static float    celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius()      : dval; }
318
+  FORCE_INLINE static float    linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; }
319
+  FORCE_INLINE static float    celsiusval(const char c, const float dval=0){ return seenval(c) ? value_celsius()      : dval; }
320
 
320
 
321
 };
321
 };
322
 
322
 

+ 1
- 1
Marlin/src/gcode/temperature/M104_M109.cpp Просмотреть файл

225
       // break after MIN_COOLING_SLOPE_TIME seconds
225
       // break after MIN_COOLING_SLOPE_TIME seconds
226
       // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG
226
       // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG
227
       if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
227
       if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
228
-        if (old_temp - temp < MIN_COOLING_SLOPE_DEG) break;
228
+        if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG)) break;
229
         next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME;
229
         next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME;
230
         old_temp = temp;
230
         old_temp = temp;
231
       }
231
       }

+ 2
- 2
Marlin/src/gcode/temperature/M140_M190.cpp Просмотреть файл

82
     #define TEMP_BED_CONDITIONS (wants_to_cool ? thermalManager.isCoolingBed() : thermalManager.isHeatingBed())
82
     #define TEMP_BED_CONDITIONS (wants_to_cool ? thermalManager.isCoolingBed() : thermalManager.isHeatingBed())
83
   #endif
83
   #endif
84
 
84
 
85
-  float target_temp = -1.0, old_temp = 9999.0;
85
+  float target_temp = -1, old_temp = 9999;
86
   bool wants_to_cool = false;
86
   bool wants_to_cool = false;
87
   wait_for_heatup = true;
87
   wait_for_heatup = true;
88
   millis_t now, next_temp_ms = 0, next_cool_check_ms = 0;
88
   millis_t now, next_temp_ms = 0, next_cool_check_ms = 0;
163
       // Break after MIN_COOLING_SLOPE_TIME_BED seconds
163
       // Break after MIN_COOLING_SLOPE_TIME_BED seconds
164
       // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_BED
164
       // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_BED
165
       if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
165
       if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
166
-        if (old_temp - temp < MIN_COOLING_SLOPE_DEG_BED) break;
166
+        if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG_BED)) break;
167
         next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME_BED;
167
         next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME_BED;
168
         old_temp = temp;
168
         old_temp = temp;
169
       }
169
       }

+ 0
- 19
Marlin/src/inc/Conditionals_post.h Просмотреть файл

1353
   #endif
1353
   #endif
1354
 #endif
1354
 #endif
1355
 
1355
 
1356
-// Use float instead of double. Needs profiling.
1357
-#if defined(ARDUINO_ARCH_SAM) && ENABLED(DELTA_FAST_SQRT)
1358
-  #undef ATAN2
1359
-  #undef FABS
1360
-  #undef POW
1361
-  #undef SQRT
1362
-  #undef CEIL
1363
-  #undef FLOOR
1364
-  #undef LROUND
1365
-  #undef FMOD
1366
-  #define ATAN2(y, x) atan2f(y, x)
1367
-  #define POW(x, y) powf(x, y)
1368
-  #define SQRT(x) sqrtf(x)
1369
-  #define CEIL(x) ceilf(x)
1370
-  #define FLOOR(x) floorf(x)
1371
-  #define LROUND(x) lroundf(x)
1372
-  #define FMOD(x, y) fmodf(x, y)
1373
-#endif
1374
-
1375
 // Number of VFAT entries used. Each entry has 13 UTF-16 characters
1356
 // Number of VFAT entries used. Each entry has 13 UTF-16 characters
1376
 #if ENABLED(SCROLL_LONG_FILENAMES)
1357
 #if ENABLED(SCROLL_LONG_FILENAMES)
1377
   #define MAX_VFAT_ENTRIES (5)
1358
   #define MAX_VFAT_ENTRIES (5)

+ 1
- 1
Marlin/src/lcd/dogm/status_screen_DOGM.h Просмотреть файл

72
   }
72
   }
73
 
73
 
74
   if (PAGE_CONTAINS(21, 28)) {
74
   if (PAGE_CONTAINS(21, 28)) {
75
-    _draw_centered_temp(0.5 + (
75
+    _draw_centered_temp(0.5f + (
76
         #if HAS_HEATED_BED
76
         #if HAS_HEATED_BED
77
           isBed ? thermalManager.degBed() :
77
           isBed ? thermalManager.degBed() :
78
         #endif
78
         #endif

+ 64
- 64
Marlin/src/lcd/ultralcd.cpp Просмотреть файл

479
 
479
 
480
   #if IS_KINEMATIC
480
   #if IS_KINEMATIC
481
     bool processing_manual_move = false;
481
     bool processing_manual_move = false;
482
-    float manual_move_offset = 0.0;
482
+    float manual_move_offset = 0;
483
   #else
483
   #else
484
     constexpr bool processing_manual_move = false;
484
     constexpr bool processing_manual_move = false;
485
   #endif
485
   #endif
1285
         ubl_encoderPosition = (ubl.encoder_diff > 0) ? 1 : -1;
1285
         ubl_encoderPosition = (ubl.encoder_diff > 0) ? 1 : -1;
1286
         ubl.encoder_diff = 0;
1286
         ubl.encoder_diff = 0;
1287
 
1287
 
1288
-        mesh_edit_accumulator += float(ubl_encoderPosition) * 0.005 / 2.0;
1288
+        mesh_edit_accumulator += float(ubl_encoderPosition) * 0.005f * 0.5f;
1289
         mesh_edit_value = mesh_edit_accumulator;
1289
         mesh_edit_value = mesh_edit_accumulator;
1290
         encoderPosition = 0;
1290
         encoderPosition = 0;
1291
         lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT;
1291
         lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT;
1292
 
1292
 
1293
-        const int32_t rounded = (int32_t)(mesh_edit_value * 1000.0);
1294
-        mesh_edit_value = float(rounded - (rounded % 5L)) / 1000.0;
1293
+        const int32_t rounded = (int32_t)(mesh_edit_value * 1000);
1294
+        mesh_edit_value = float(rounded - (rounded % 5L)) / 1000;
1295
       }
1295
       }
1296
 
1296
 
1297
       if (lcdDrawUpdate) {
1297
       if (lcdDrawUpdate) {
1419
     // Leveling Fade Height
1419
     // Leveling Fade Height
1420
     //
1420
     //
1421
     #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(SLIM_LCD_MENUS)
1421
     #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(SLIM_LCD_MENUS)
1422
-      MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height);
1422
+      MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
1423
     #endif
1423
     #endif
1424
 
1424
 
1425
     //
1425
     //
1978
       //
1978
       //
1979
       if (encoderPosition) {
1979
       if (encoderPosition) {
1980
         const float z = current_position[Z_AXIS] + float((int32_t)encoderPosition) * (MBL_Z_STEP);
1980
         const float z = current_position[Z_AXIS] + float((int32_t)encoderPosition) * (MBL_Z_STEP);
1981
-        line_to_z(constrain(z, -(LCD_PROBE_Z_RANGE) * 0.5, (LCD_PROBE_Z_RANGE) * 0.5));
1981
+        line_to_z(constrain(z, -(LCD_PROBE_Z_RANGE) * 0.5f, (LCD_PROBE_Z_RANGE) * 0.5f));
1982
         lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT;
1982
         lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT;
1983
         encoderPosition = 0;
1983
         encoderPosition = 0;
1984
       }
1984
       }
1988
       //
1988
       //
1989
       if (lcdDrawUpdate) {
1989
       if (lcdDrawUpdate) {
1990
         const float v = current_position[Z_AXIS];
1990
         const float v = current_position[Z_AXIS];
1991
-        lcd_implementation_drawedit(PSTR(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001 : 0.0001), '+'));
1991
+        lcd_implementation_drawedit(PSTR(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001f : 0.0001f), '+'));
1992
       }
1992
       }
1993
     }
1993
     }
1994
 
1994
 
2571
       MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu);
2571
       MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu);
2572
       MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W"));
2572
       MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W"));
2573
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2573
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2574
-        MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height);
2574
+        MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
2575
       #endif
2575
       #endif
2576
       END_MENU();
2576
       END_MENU();
2577
     }
2577
     }
2627
 
2627
 
2628
       // Z Fade Height
2628
       // Z Fade Height
2629
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2629
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2630
-        MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height);
2630
+        MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
2631
       #endif
2631
       #endif
2632
 
2632
 
2633
       //
2633
       //
2713
         MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &new_level_state, _lcd_toggle_bed_leveling);
2713
         MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &new_level_state, _lcd_toggle_bed_leveling);
2714
       }
2714
       }
2715
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2715
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2716
-        MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height);
2716
+        MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float3, MSG_Z_FADE_HEIGHT, &new_z_fade_height, 0, 100, _lcd_set_z_fade_height);
2717
       #endif
2717
       #endif
2718
 
2718
 
2719
     #endif
2719
     #endif
2877
     void lcd_delta_settings() {
2877
     void lcd_delta_settings() {
2878
       START_MENU();
2878
       START_MENU();
2879
       MENU_BACK(MSG_DELTA_CALIBRATE);
2879
       MENU_BACK(MSG_DELTA_CALIBRATE);
2880
-      MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_HEIGHT, &delta_height, delta_height - 10.0, delta_height + 10.0, _recalc_delta_settings);
2881
-      MENU_ITEM_EDIT_CALLBACK(float43, "Ex", &delta_endstop_adj[A_AXIS], -5.0, 5.0, _recalc_delta_settings);
2882
-      MENU_ITEM_EDIT_CALLBACK(float43, "Ey", &delta_endstop_adj[B_AXIS], -5.0, 5.0, _recalc_delta_settings);
2883
-      MENU_ITEM_EDIT_CALLBACK(float43, "Ez", &delta_endstop_adj[C_AXIS], -5.0, 5.0, _recalc_delta_settings);
2884
-      MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_RADIUS, &delta_radius, delta_radius - 5.0, delta_radius + 5.0, _recalc_delta_settings);
2885
-      MENU_ITEM_EDIT_CALLBACK(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5.0, 5.0, _recalc_delta_settings);
2886
-      MENU_ITEM_EDIT_CALLBACK(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5.0, 5.0, _recalc_delta_settings);
2887
-      MENU_ITEM_EDIT_CALLBACK(float43, "Tz", &delta_tower_angle_trim[C_AXIS], -5.0, 5.0, _recalc_delta_settings);
2888
-      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);
2880
+      MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_HEIGHT, &delta_height, delta_height - 10, delta_height + 10, _recalc_delta_settings);
2881
+      MENU_ITEM_EDIT_CALLBACK(float43, "Ex", &delta_endstop_adj[A_AXIS], -5, 5, _recalc_delta_settings);
2882
+      MENU_ITEM_EDIT_CALLBACK(float43, "Ey", &delta_endstop_adj[B_AXIS], -5, 5, _recalc_delta_settings);
2883
+      MENU_ITEM_EDIT_CALLBACK(float43, "Ez", &delta_endstop_adj[C_AXIS], -5, 5, _recalc_delta_settings);
2884
+      MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_RADIUS, &delta_radius, delta_radius - 5, delta_radius + 5, _recalc_delta_settings);
2885
+      MENU_ITEM_EDIT_CALLBACK(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5, 5, _recalc_delta_settings);
2886
+      MENU_ITEM_EDIT_CALLBACK(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5, 5, _recalc_delta_settings);
2887
+      MENU_ITEM_EDIT_CALLBACK(float43, "Tz", &delta_tower_angle_trim[C_AXIS], -5, 5, _recalc_delta_settings);
2888
+      MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_DIAG_ROD, &delta_diagonal_rod, delta_diagonal_rod - 5, delta_diagonal_rod + 5, _recalc_delta_settings);
2889
       END_MENU();
2889
       END_MENU();
2890
     }
2890
     }
2891
 
2891
 
2981
       #endif
2981
       #endif
2982
           manual_move_e_index = eindex >= 0 ? eindex : active_extruder;
2982
           manual_move_e_index = eindex >= 0 ? eindex : active_extruder;
2983
     #endif
2983
     #endif
2984
-    manual_move_start_time = millis() + (move_menu_scale < 0.99 ? 0UL : 250UL); // delay for bigger moves
2984
+    manual_move_start_time = millis() + (move_menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves
2985
     manual_move_axis = (int8_t)axis;
2985
     manual_move_axis = (int8_t)axis;
2986
   }
2986
   }
2987
 
2987
 
3065
           + manual_move_offset
3065
           + manual_move_offset
3066
         #endif
3066
         #endif
3067
       , axis);
3067
       , axis);
3068
-      lcd_implementation_drawedit(name, move_menu_scale >= 0.1 ? ftostr41sign(pos) : ftostr43sign(pos));
3068
+      lcd_implementation_drawedit(name, move_menu_scale >= 0.1f ? ftostr41sign(pos) : ftostr43sign(pos));
3069
     }
3069
     }
3070
   }
3070
   }
3071
   void lcd_move_x() { _lcd_move_xyz(PSTR(MSG_MOVE_X), X_AXIS); }
3071
   void lcd_move_x() { _lcd_move_xyz(PSTR(MSG_MOVE_X), X_AXIS); }
3150
     move_menu_scale = scale;
3150
     move_menu_scale = scale;
3151
     lcd_goto_screen(_manual_move_func_ptr);
3151
     lcd_goto_screen(_manual_move_func_ptr);
3152
   }
3152
   }
3153
-  void lcd_move_menu_10mm() { _goto_manual_move(10.0); }
3154
-  void lcd_move_menu_1mm()  { _goto_manual_move( 1.0); }
3155
-  void lcd_move_menu_01mm() { _goto_manual_move( 0.1); }
3153
+  void lcd_move_menu_10mm() { _goto_manual_move(10); }
3154
+  void lcd_move_menu_1mm()  { _goto_manual_move( 1); }
3155
+  void lcd_move_menu_01mm() { _goto_manual_move( 0.1f); }
3156
 
3156
 
3157
   void _lcd_move_distance_menu(const AxisEnum axis, const screenFunc_t func) {
3157
   void _lcd_move_distance_menu(const AxisEnum axis, const screenFunc_t func) {
3158
     _manual_move_func_ptr = func;
3158
     _manual_move_func_ptr = func;
3527
     //
3527
     //
3528
     #if ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND
3528
     #if ENABLED(AUTOTEMP) && HAS_TEMP_HOTEND
3529
       MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &planner.autotemp_enabled);
3529
       MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &planner.autotemp_enabled);
3530
-      MENU_ITEM_EDIT(float3, MSG_MIN, &planner.autotemp_min, 0, HEATER_0_MAXTEMP - 15);
3531
-      MENU_ITEM_EDIT(float3, MSG_MAX, &planner.autotemp_max, 0, HEATER_0_MAXTEMP - 15);
3532
-      MENU_ITEM_EDIT(float52, MSG_FACTOR, &planner.autotemp_factor, 0.0, 1.0);
3530
+      MENU_ITEM_EDIT(float3, MSG_MIN, &planner.autotemp_min, 0, float(HEATER_0_MAXTEMP) - 15);
3531
+      MENU_ITEM_EDIT(float3, MSG_MAX, &planner.autotemp_max, 0, float(HEATER_0_MAXTEMP) - 15);
3532
+      MENU_ITEM_EDIT(float52, MSG_FACTOR, &planner.autotemp_factor, 0, 1);
3533
     #endif
3533
     #endif
3534
 
3534
 
3535
     //
3535
     //
3546
         raw_Ki = unscalePID_i(PID_PARAM(Ki, eindex)); \
3546
         raw_Ki = unscalePID_i(PID_PARAM(Ki, eindex)); \
3547
         raw_Kd = unscalePID_d(PID_PARAM(Kd, eindex)); \
3547
         raw_Kd = unscalePID_d(PID_PARAM(Kd, eindex)); \
3548
         MENU_ITEM_EDIT(float52sign, MSG_PID_P ELABEL, &PID_PARAM(Kp, eindex), 1, 9990); \
3548
         MENU_ITEM_EDIT(float52sign, MSG_PID_P ELABEL, &PID_PARAM(Kp, eindex), 1, 9990); \
3549
-        MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_I ELABEL, &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E ## eindex); \
3549
+        MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_I ELABEL, &raw_Ki, 0.01f, 9990, copy_and_scalePID_i_E ## eindex); \
3550
         MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_D ELABEL, &raw_Kd, 1, 9990, copy_and_scalePID_d_E ## eindex)
3550
         MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_PID_D ELABEL, &raw_Kd, 1, 9990, copy_and_scalePID_d_E ## eindex)
3551
 
3551
 
3552
       #if ENABLED(PID_EXTRUSION_SCALING)
3552
       #if ENABLED(PID_EXTRUSION_SCALING)
3668
         if (e == active_extruder)
3668
         if (e == active_extruder)
3669
           _planner_refresh_positioning();
3669
           _planner_refresh_positioning();
3670
         else
3670
         else
3671
-          planner.steps_to_mm[E_AXIS + e] = 1.0 / planner.axis_steps_per_mm[E_AXIS + e];
3671
+          planner.steps_to_mm[E_AXIS + e] = 1.0f / planner.axis_steps_per_mm[E_AXIS + e];
3672
       }
3672
       }
3673
       void _planner_refresh_e0_positioning() { _planner_refresh_e_positioning(0); }
3673
       void _planner_refresh_e0_positioning() { _planner_refresh_e_positioning(0); }
3674
       void _planner_refresh_e1_positioning() { _planner_refresh_e_positioning(1); }
3674
       void _planner_refresh_e1_positioning() { _planner_refresh_e_positioning(1); }
3764
       MENU_BACK(MSG_MOTION);
3764
       MENU_BACK(MSG_MOTION);
3765
 
3765
 
3766
       #if ENABLED(JUNCTION_DEVIATION)
3766
       #if ENABLED(JUNCTION_DEVIATION)
3767
-        MENU_ITEM_EDIT_CALLBACK(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.01, 0.3, planner.recalculate_max_e_jerk);
3767
+        MENU_ITEM_EDIT_CALLBACK(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.01f, 0.3f, planner.recalculate_max_e_jerk);
3768
       #else
3768
       #else
3769
         MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VA_JERK, &planner.max_jerk[A_AXIS], 1, 990);
3769
         MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VA_JERK, &planner.max_jerk[A_AXIS], 1, 990);
3770
         MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VB_JERK, &planner.max_jerk[B_AXIS], 1, 990);
3770
         MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VB_JERK, &planner.max_jerk[B_AXIS], 1, 990);
3771
         #if ENABLED(DELTA)
3771
         #if ENABLED(DELTA)
3772
           MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 1, 990);
3772
           MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 1, 990);
3773
         #else
3773
         #else
3774
-          MENU_MULTIPLIER_ITEM_EDIT(float52sign, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 0.1, 990);
3774
+          MENU_MULTIPLIER_ITEM_EDIT(float52sign, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 0.1f, 990);
3775
         #endif
3775
         #endif
3776
         MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_jerk[E_AXIS], 1, 990);
3776
         MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_jerk[E_AXIS], 1, 990);
3777
       #endif
3777
       #endif
3869
 
3869
 
3870
         if (parser.volumetric_enabled) {
3870
         if (parser.volumetric_enabled) {
3871
           #if EXTRUDERS == 1
3871
           #if EXTRUDERS == 1
3872
-            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[0], 1.5, 3.25, planner.calculate_volumetric_multipliers);
3872
+            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[0], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
3873
           #else // EXTRUDERS > 1
3873
           #else // EXTRUDERS > 1
3874
-            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[active_extruder], 1.5, 3.25, planner.calculate_volumetric_multipliers);
3875
-            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E1, &planner.filament_size[0], 1.5, 3.25, planner.calculate_volumetric_multipliers);
3876
-            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E2, &planner.filament_size[1], 1.5, 3.25, planner.calculate_volumetric_multipliers);
3874
+            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM, &planner.filament_size[active_extruder], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
3875
+            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E1, &planner.filament_size[0], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
3876
+            MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E2, &planner.filament_size[1], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
3877
             #if EXTRUDERS > 2
3877
             #if EXTRUDERS > 2
3878
-              MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E3, &planner.filament_size[2], 1.5, 3.25, planner.calculate_volumetric_multipliers);
3878
+              MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E3, &planner.filament_size[2], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
3879
             #if EXTRUDERS > 3
3879
             #if EXTRUDERS > 3
3880
-              MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E4, &planner.filament_size[3], 1.5, 3.25, planner.calculate_volumetric_multipliers);
3880
+              MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E4, &planner.filament_size[3], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
3881
               #if EXTRUDERS > 4
3881
               #if EXTRUDERS > 4
3882
-                  MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E5, &planner.filament_size[4], 1.5, 3.25, planner.calculate_volumetric_multipliers);
3882
+                  MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_DIAM MSG_DIAM_E5, &planner.filament_size[4], 1.5f, 3.25f, planner.calculate_volumetric_multipliers);
3883
                 #endif // EXTRUDERS > 4
3883
                 #endif // EXTRUDERS > 4
3884
               #endif // EXTRUDERS > 3
3884
               #endif // EXTRUDERS > 3
3885
             #endif // EXTRUDERS > 2
3885
             #endif // EXTRUDERS > 2
3892
           #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
3892
           #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
3893
             EXTRUDE_MAXLENGTH
3893
             EXTRUDE_MAXLENGTH
3894
           #else
3894
           #else
3895
-            999.0f
3895
+            999
3896
           #endif
3896
           #endif
3897
         ;
3897
         ;
3898
 
3898
 
3899
         #if EXTRUDERS == 1
3899
         #if EXTRUDERS == 1
3900
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[0], 0.0, extrude_maxlength);
3900
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[0], 0, extrude_maxlength);
3901
         #else // EXTRUDERS > 1
3901
         #else // EXTRUDERS > 1
3902
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[active_extruder], 0.0, extrude_maxlength);
3903
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E1, &filament_change_unload_length[0], 0.0, extrude_maxlength);
3904
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E2, &filament_change_unload_length[1], 0.0, extrude_maxlength);
3902
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD, &filament_change_unload_length[active_extruder], 0, extrude_maxlength);
3903
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E1, &filament_change_unload_length[0], 0, extrude_maxlength);
3904
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E2, &filament_change_unload_length[1], 0, extrude_maxlength);
3905
           #if EXTRUDERS > 2
3905
           #if EXTRUDERS > 2
3906
-            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E3, &filament_change_unload_length[2], 0.0, extrude_maxlength);
3906
+            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E3, &filament_change_unload_length[2], 0, extrude_maxlength);
3907
           #if EXTRUDERS > 3
3907
           #if EXTRUDERS > 3
3908
-            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E4, &filament_change_unload_length[3], 0.0, extrude_maxlength);
3908
+            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E4, &filament_change_unload_length[3], 0, extrude_maxlength);
3909
             #if EXTRUDERS > 4
3909
             #if EXTRUDERS > 4
3910
-                MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E5, &filament_change_unload_length[4], 0.0, extrude_maxlength);
3910
+                MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_UNLOAD MSG_DIAM_E5, &filament_change_unload_length[4], 0, extrude_maxlength);
3911
               #endif // EXTRUDERS > 4
3911
               #endif // EXTRUDERS > 4
3912
             #endif // EXTRUDERS > 3
3912
             #endif // EXTRUDERS > 3
3913
           #endif // EXTRUDERS > 2
3913
           #endif // EXTRUDERS > 2
3914
         #endif // EXTRUDERS > 1
3914
         #endif // EXTRUDERS > 1
3915
 
3915
 
3916
         #if EXTRUDERS == 1
3916
         #if EXTRUDERS == 1
3917
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[0], 0.0, extrude_maxlength);
3917
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[0], 0, extrude_maxlength);
3918
         #else // EXTRUDERS > 1
3918
         #else // EXTRUDERS > 1
3919
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[active_extruder], 0.0, extrude_maxlength);
3920
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E1, &filament_change_load_length[0], 0.0, extrude_maxlength);
3921
-          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E2, &filament_change_load_length[1], 0.0, extrude_maxlength);
3919
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD, &filament_change_load_length[active_extruder], 0, extrude_maxlength);
3920
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E1, &filament_change_load_length[0], 0, extrude_maxlength);
3921
+          MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E2, &filament_change_load_length[1], 0, extrude_maxlength);
3922
           #if EXTRUDERS > 2
3922
           #if EXTRUDERS > 2
3923
-            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E3, &filament_change_load_length[2], 0.0, extrude_maxlength);
3923
+            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E3, &filament_change_load_length[2], 0, extrude_maxlength);
3924
           #if EXTRUDERS > 3
3924
           #if EXTRUDERS > 3
3925
-            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E4, &filament_change_load_length[3], 0.0, extrude_maxlength);
3925
+            MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E4, &filament_change_load_length[3], 0, extrude_maxlength);
3926
             #if EXTRUDERS > 4
3926
             #if EXTRUDERS > 4
3927
-                MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E5, &filament_change_load_length[4], 0.0, extrude_maxlength);
3927
+                MENU_MULTIPLIER_ITEM_EDIT(float3, MSG_FILAMENT_LOAD MSG_DIAM_E5, &filament_change_load_length[4], 0, extrude_maxlength);
3928
               #endif // EXTRUDERS > 4
3928
               #endif // EXTRUDERS > 4
3929
             #endif // EXTRUDERS > 3
3929
             #endif // EXTRUDERS > 3
3930
           #endif // EXTRUDERS > 2
3930
           #endif // EXTRUDERS > 2
4824
       if ((int32_t)encoderPosition < 0) encoderPosition = 0; \
4824
       if ((int32_t)encoderPosition < 0) encoderPosition = 0; \
4825
       if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \
4825
       if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \
4826
       if (lcdDrawUpdate) \
4826
       if (lcdDrawUpdate) \
4827
-        lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale))); \
4827
+        lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) * (1.0f / _scale))); \
4828
       if (lcd_clicked || (liveEdit && lcdDrawUpdate)) { \
4828
       if (lcd_clicked || (liveEdit && lcdDrawUpdate)) { \
4829
-        _type value = ((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale); \
4829
+        _type value = ((_type)((int32_t)encoderPosition + minEditValue)) * (1.0f / _scale); \
4830
         if (editValue != NULL) *((_type*)editValue) = value; \
4830
         if (editValue != NULL) *((_type*)editValue) = value; \
4831
         if (callbackFunc && (liveEdit || lcd_clicked)) (*callbackFunc)(); \
4831
         if (callbackFunc && (liveEdit || lcd_clicked)) (*callbackFunc)(); \
4832
         if (lcd_clicked) lcd_goto_previous_menu(); \
4832
         if (lcd_clicked) lcd_goto_previous_menu(); \
4857
 
4857
 
4858
   DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1);
4858
   DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1);
4859
   DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1);
4859
   DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1);
4860
-  DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1.0);
4861
-  DEFINE_MENU_EDIT_TYPE(float, float52, ftostr52, 100.0);
4862
-  DEFINE_MENU_EDIT_TYPE(float, float43, ftostr43sign, 1000.0);
4863
-  DEFINE_MENU_EDIT_TYPE(float, float5, ftostr5rj, 0.01);
4864
-  DEFINE_MENU_EDIT_TYPE(float, float51, ftostr51sign, 10.0);
4865
-  DEFINE_MENU_EDIT_TYPE(float, float52sign, ftostr52sign, 100.0);
4866
-  DEFINE_MENU_EDIT_TYPE(float, float62, ftostr62rj, 100.0);
4867
-  DEFINE_MENU_EDIT_TYPE(uint32_t, long5, ftostr5rj, 0.01);
4860
+  DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1);
4861
+  DEFINE_MENU_EDIT_TYPE(float, float52, ftostr52, 100);
4862
+  DEFINE_MENU_EDIT_TYPE(float, float43, ftostr43sign, 1000);
4863
+  DEFINE_MENU_EDIT_TYPE(float, float5, ftostr5rj, 0.01f);
4864
+  DEFINE_MENU_EDIT_TYPE(float, float51, ftostr51sign, 10);
4865
+  DEFINE_MENU_EDIT_TYPE(float, float52sign, ftostr52sign, 100);
4866
+  DEFINE_MENU_EDIT_TYPE(float, float62, ftostr62rj, 100);
4867
+  DEFINE_MENU_EDIT_TYPE(uint32_t, long5, ftostr5rj, 0.01f);
4868
 
4868
 
4869
   /**
4869
   /**
4870
    *
4870
    *
5228
               if (lastEncoderMovementMillis) {
5228
               if (lastEncoderMovementMillis) {
5229
                 // Note that the rate is always calculated between two passes through the
5229
                 // Note that the rate is always calculated between two passes through the
5230
                 // loop and that the abs of the encoderDiff value is tracked.
5230
                 // loop and that the abs of the encoderDiff value is tracked.
5231
-                float encoderStepRate = float(encoderMovementSteps) / float(ms - lastEncoderMovementMillis) * 1000.0;
5231
+                float encoderStepRate = float(encoderMovementSteps) / float(ms - lastEncoderMovementMillis) * 1000;
5232
 
5232
 
5233
                 if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC)     encoderMultiplier = 100;
5233
                 if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC)     encoderMultiplier = 100;
5234
                 else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;
5234
                 else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;

+ 1
- 1
Marlin/src/libs/vector_3.cpp Просмотреть файл

69
 float vector_3::get_length() { return SQRT(sq(x) + sq(y) + sq(z)); }
69
 float vector_3::get_length() { return SQRT(sq(x) + sq(y) + sq(z)); }
70
 
70
 
71
 void vector_3::normalize() {
71
 void vector_3::normalize() {
72
-  const float inv_length = 1.0 / get_length();
72
+  const float inv_length = RSQRT(sq(x) + sq(y) + sq(z));
73
   x *= inv_length;
73
   x *= inv_length;
74
   y *= inv_length;
74
   y *= inv_length;
75
   z *= inv_length;
75
   z *= inv_length;

+ 6
- 6
Marlin/src/module/configuration_store.cpp Просмотреть файл

417
     EEPROM_WRITE(planner.min_travel_feedrate_mm_s);
417
     EEPROM_WRITE(planner.min_travel_feedrate_mm_s);
418
 
418
 
419
     #if ENABLED(JUNCTION_DEVIATION)
419
     #if ENABLED(JUNCTION_DEVIATION)
420
-      const float planner_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK };
420
+      const float planner_max_jerk[] = { float(DEFAULT_XJERK), float(DEFAULT_YJERK), float(DEFAULT_ZJERK), float(DEFAULT_EJERK) };
421
       EEPROM_WRITE(planner_max_jerk);
421
       EEPROM_WRITE(planner_max_jerk);
422
       EEPROM_WRITE(planner.junction_deviation_mm);
422
       EEPROM_WRITE(planner.junction_deviation_mm);
423
     #else
423
     #else
424
       EEPROM_WRITE(planner.max_jerk);
424
       EEPROM_WRITE(planner.max_jerk);
425
-      dummy = 0.02;
425
+      dummy = 0.02f;
426
       EEPROM_WRITE(dummy);
426
       EEPROM_WRITE(dummy);
427
     #endif
427
     #endif
428
 
428
 
488
     #if ABL_PLANAR
488
     #if ABL_PLANAR
489
       EEPROM_WRITE(planner.bed_level_matrix);
489
       EEPROM_WRITE(planner.bed_level_matrix);
490
     #else
490
     #else
491
-      dummy = 0.0;
491
+      dummy = 0.0f;
492
       for (uint8_t q = 9; q--;) EEPROM_WRITE(dummy);
492
       for (uint8_t q = 9; q--;) EEPROM_WRITE(dummy);
493
     #endif
493
     #endif
494
 
494
 
974
       eeprom_error = true;
974
       eeprom_error = true;
975
     }
975
     }
976
     else {
976
     else {
977
-      float dummy = 0;
977
+      float dummy = 0.0f;
978
       #if DISABLED(AUTO_BED_LEVELING_UBL) || DISABLED(FWRETRACT) || ENABLED(NO_VOLUMETRICS)
978
       #if DISABLED(AUTO_BED_LEVELING_UBL) || DISABLED(FWRETRACT) || ENABLED(NO_VOLUMETRICS)
979
         bool dummyb;
979
         bool dummyb;
980
       #endif
980
       #endif
1733
   planner.min_travel_feedrate_mm_s = DEFAULT_MINTRAVELFEEDRATE;
1733
   planner.min_travel_feedrate_mm_s = DEFAULT_MINTRAVELFEEDRATE;
1734
 
1734
 
1735
   #if ENABLED(JUNCTION_DEVIATION)
1735
   #if ENABLED(JUNCTION_DEVIATION)
1736
-    planner.junction_deviation_mm = JUNCTION_DEVIATION_MM;
1736
+    planner.junction_deviation_mm = float(JUNCTION_DEVIATION_MM);
1737
   #else
1737
   #else
1738
     planner.max_jerk[X_AXIS] = DEFAULT_XJERK;
1738
     planner.max_jerk[X_AXIS] = DEFAULT_XJERK;
1739
     planner.max_jerk[Y_AXIS] = DEFAULT_YJERK;
1739
     planner.max_jerk[Y_AXIS] = DEFAULT_YJERK;
1835
       HOTEND_LOOP()
1835
       HOTEND_LOOP()
1836
     #endif
1836
     #endif
1837
     {
1837
     {
1838
-      PID_PARAM(Kp, e) = DEFAULT_Kp;
1838
+      PID_PARAM(Kp, e) = float(DEFAULT_Kp);
1839
       PID_PARAM(Ki, e) = scalePID_i(DEFAULT_Ki);
1839
       PID_PARAM(Ki, e) = scalePID_i(DEFAULT_Ki);
1840
       PID_PARAM(Kd, e) = scalePID_d(DEFAULT_Kd);
1840
       PID_PARAM(Kd, e) = scalePID_d(DEFAULT_Kd);
1841
       #if ENABLED(PID_EXTRUSION_SCALING)
1841
       #if ENABLED(PID_EXTRUSION_SCALING)

+ 17
- 40
Marlin/src/module/delta.cpp Просмотреть файл

90
  *
90
  *
91
  * - Disable the home_offset (M206) and/or position_shift (G92)
91
  * - Disable the home_offset (M206) and/or position_shift (G92)
92
  *   features to remove up to 12 float additions.
92
  *   features to remove up to 12 float additions.
93
- *
94
- * - Use a fast-inverse-sqrt function and add the reciprocal.
95
- *   (see above)
96
  */
93
  */
97
 
94
 
98
-#if ENABLED(DELTA_FAST_SQRT) && defined(__AVR__)
99
-  /**
100
-   * Fast inverse sqrt from Quake III Arena
101
-   * See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
102
-   */
103
-  float Q_rsqrt(float number) {
104
-    long i;
105
-    float x2, y;
106
-    const float threehalfs = 1.5f;
107
-    x2 = number * 0.5f;
108
-    y  = number;
109
-    i  = * ( long * ) &y;                       // evil floating point bit level hacking
110
-    i  = 0x5F3759DF - ( i >> 1 );               // what the f***?
111
-    y  = * ( float * ) &i;
112
-    y  = y * ( threehalfs - ( x2 * y * y ) );   // 1st iteration
113
-    // y  = y * ( threehalfs - ( x2 * y * y ) );   // 2nd iteration, this can be removed
114
-    return y;
115
-  }
116
-#endif
117
-
118
 #define DELTA_DEBUG(VAR) do { \
95
 #define DELTA_DEBUG(VAR) do { \
119
     SERIAL_ECHOPAIR("cartesian X:", VAR[X_AXIS]); \
96
     SERIAL_ECHOPAIR("cartesian X:", VAR[X_AXIS]); \
120
     SERIAL_ECHOPAIR(" Y:", VAR[Y_AXIS]);          \
97
     SERIAL_ECHOPAIR(" Y:", VAR[Y_AXIS]);          \
178
  *
155
  *
179
  * The result is stored in the cartes[] array.
156
  * The result is stored in the cartes[] array.
180
  */
157
  */
181
-void forward_kinematics_DELTA(float z1, float z2, float z3) {
158
+void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3) {
182
   // Create a vector in old coordinates along x axis of new coordinate
159
   // Create a vector in old coordinates along x axis of new coordinate
183
-  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 };
160
+  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 };
184
 
161
 
185
-  // Get the Magnitude of vector.
186
-  float d = SQRT( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) );
162
+  // Get the reciprocal of Magnitude of vector.
163
+  const float d2 = sq(p12[0]) + sq(p12[1]) + sq(p12[2]), inv_d = RSQRT(d2);
187
 
164
 
188
-  // Create unit vector by dividing by magnitude.
189
-  float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d };
165
+  // Create unit vector by multiplying by the inverse of the magnitude.
166
+  const float ex[3] = { p12[0] * inv_d, p12[1] * inv_d, p12[2] * inv_d };
190
 
167
 
191
   // Get the vector from the origin of the new system to the third point.
168
   // Get the vector from the origin of the new system to the third point.
192
-  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 };
169
+  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 };
193
 
170
 
194
   // Use the dot product to find the component of this vector on the X axis.
171
   // Use the dot product to find the component of this vector on the X axis.
195
-  float i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2];
172
+  const float i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2];
196
 
173
 
197
   // Create a vector along the x axis that represents the x component of p13.
174
   // Create a vector along the x axis that represents the x component of p13.
198
-  float iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i };
175
+  const float iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i };
199
 
176
 
200
   // Subtract the X component from the original vector leaving only Y. We use the
177
   // Subtract the X component from the original vector leaving only Y. We use the
201
   // variable that will be the unit vector after we scale it.
178
   // variable that will be the unit vector after we scale it.
202
   float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
179
   float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
203
 
180
 
204
-  // The magnitude of Y component
205
-  float j = SQRT( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) );
181
+  // The magnitude and the inverse of the magnitude of Y component
182
+  const float j2 = sq(ey[0]) + sq(ey[1]) + sq(ey[2]), inv_j = RSQRT(j2);
206
 
183
 
207
   // Convert to a unit vector
184
   // Convert to a unit vector
208
-  ey[0] /= j; ey[1] /= j;  ey[2] /= j;
185
+  ey[0] *= inv_j; ey[1] *= inv_j; ey[2] *= inv_j;
209
 
186
 
210
   // The cross product of the unit x and y is the unit z
187
   // The cross product of the unit x and y is the unit z
211
   // float[] ez = vectorCrossProd(ex, ey);
188
   // float[] ez = vectorCrossProd(ex, ey);
212
-  float ez[3] = {
189
+  const float ez[3] = {
213
     ex[1] * ey[2] - ex[2] * ey[1],
190
     ex[1] * ey[2] - ex[2] * ey[1],
214
     ex[2] * ey[0] - ex[0] * ey[2],
191
     ex[2] * ey[0] - ex[0] * ey[2],
215
     ex[0] * ey[1] - ex[1] * ey[0]
192
     ex[0] * ey[1] - ex[1] * ey[0]
217
 
194
 
218
   // We now have the d, i and j values defined in Wikipedia.
195
   // We now have the d, i and j values defined in Wikipedia.
219
   // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
196
   // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
220
-  float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + sq(d)) / (d * 2),
221
-        Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + HYPOT2(i, j)) / 2 - i * Xnew) / j,
222
-        Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew));
197
+  const float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + d2) * inv_d * 0.5,
198
+              Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + sq(i) + j2) * 0.5 - i * Xnew) * inv_j,
199
+              Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew));
223
 
200
 
224
   // Start from the origin of the old coordinates and add vectors in the
201
   // Start from the origin of the old coordinates and add vectors in the
225
   // old coords that represent the Xnew, Ynew and Znew to find the point
202
   // old coords that represent the Xnew, Ynew and Znew to find the point
226
   // in the old system.
203
   // in the old system.
227
   cartes[X_AXIS] = delta_tower[A_AXIS][X_AXIS] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew;
204
   cartes[X_AXIS] = delta_tower[A_AXIS][X_AXIS] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew;
228
   cartes[Y_AXIS] = delta_tower[A_AXIS][Y_AXIS] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew;
205
   cartes[Y_AXIS] = delta_tower[A_AXIS][Y_AXIS] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew;
229
-  cartes[Z_AXIS] =             z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew;
206
+  cartes[Z_AXIS] =                          z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew;
230
 }
207
 }
231
 
208
 
232
 #if ENABLED(SENSORLESS_HOMING)
209
 #if ENABLED(SENSORLESS_HOMING)

+ 4
- 15
Marlin/src/module/delta.h Просмотреть файл

64
  *   (see above)
64
  *   (see above)
65
  */
65
  */
66
 
66
 
67
-#if ENABLED(DELTA_FAST_SQRT) && defined(__AVR__)
68
-  /**
69
-   * Fast inverse sqrt from Quake III Arena
70
-   * See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
71
-   */
72
-  float Q_rsqrt(float number);
73
-  #define _SQRT(n) (1.0f / Q_rsqrt(n))
74
-#else
75
-  #define _SQRT(n) SQRT(n)
76
-#endif
77
-
78
 // Macro to obtain the Z position of an individual tower
67
 // Macro to obtain the Z position of an individual tower
79
-#define DELTA_Z(V,T) V[Z_AXIS] + _SQRT(   \
68
+#define DELTA_Z(V,T) V[Z_AXIS] + SQRT(    \
80
   delta_diagonal_rod_2_tower[T] - HYPOT2( \
69
   delta_diagonal_rod_2_tower[T] - HYPOT2( \
81
       delta_tower[T][X_AXIS] - V[X_AXIS], \
70
       delta_tower[T][X_AXIS] - V[X_AXIS], \
82
       delta_tower[T][Y_AXIS] - V[Y_AXIS]  \
71
       delta_tower[T][Y_AXIS] - V[Y_AXIS]  \
83
     )                                     \
72
     )                                     \
84
   )
73
   )
85
 
74
 
86
-#define DELTA_IK(V) do {        \
75
+#define DELTA_IK(V) do {              \
87
   delta[A_AXIS] = DELTA_Z(V, A_AXIS); \
76
   delta[A_AXIS] = DELTA_Z(V, A_AXIS); \
88
   delta[B_AXIS] = DELTA_Z(V, B_AXIS); \
77
   delta[B_AXIS] = DELTA_Z(V, B_AXIS); \
89
   delta[C_AXIS] = DELTA_Z(V, C_AXIS); \
78
   delta[C_AXIS] = DELTA_Z(V, C_AXIS); \
122
  *
111
  *
123
  * The result is stored in the cartes[] array.
112
  * The result is stored in the cartes[] array.
124
  */
113
  */
125
-void forward_kinematics_DELTA(float z1, float z2, float z3);
114
+void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3);
126
 
115
 
127
-FORCE_INLINE void forward_kinematics_DELTA(float point[ABC]) {
116
+FORCE_INLINE void forward_kinematics_DELTA(const float (&point)[ABC]) {
128
   forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]);
117
   forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]);
129
 }
118
 }
130
 
119
 

+ 9
- 9
Marlin/src/module/motion.cpp Просмотреть файл

77
  *   Used by 'buffer_line_to_current_position' to do a move after changing it.
77
  *   Used by 'buffer_line_to_current_position' to do a move after changing it.
78
  *   Used by 'SYNC_PLAN_POSITION_KINEMATIC' to update 'planner.position'.
78
  *   Used by 'SYNC_PLAN_POSITION_KINEMATIC' to update 'planner.position'.
79
  */
79
  */
80
-float current_position[XYZE] = { 0.0 };
80
+float current_position[XYZE] = { 0 };
81
 
81
 
82
 /**
82
 /**
83
  * Cartesian Destination
83
  * Cartesian Destination
85
  *   and expected by functions like 'prepare_move_to_destination'.
85
  *   and expected by functions like 'prepare_move_to_destination'.
86
  *   Set with 'get_destination_from_command' or 'set_destination_from_current'.
86
  *   Set with 'get_destination_from_command' or 'set_destination_from_current'.
87
  */
87
  */
88
-float destination[XYZE] = { 0.0 };
88
+float destination[XYZE] = { 0 };
89
 
89
 
90
 
90
 
91
 // The active extruder (tool). Set with T<extruder> command.
91
 // The active extruder (tool). Set with T<extruder> command.
100
 // no other feedrate is specified. Overridden for special moves.
100
 // no other feedrate is specified. Overridden for special moves.
101
 // Set by the last G0 through G5 command's "F" parameter.
101
 // Set by the last G0 through G5 command's "F" parameter.
102
 // Functions that override this for custom moves *must always* restore it!
102
 // Functions that override this for custom moves *must always* restore it!
103
-float feedrate_mm_s = MMM_TO_MMS(1500.0);
103
+float feedrate_mm_s = MMM_TO_MMS(1500.0f);
104
 
104
 
105
 int16_t feedrate_percentage = 100;
105
 int16_t feedrate_percentage = 100;
106
 
106
 
509
      * but may produce jagged lines. Try 0.5mm, 1.0mm, and 2.0mm
509
      * but may produce jagged lines. Try 0.5mm, 1.0mm, and 2.0mm
510
      * and compare the difference.
510
      * and compare the difference.
511
      */
511
      */
512
-    #define SCARA_MIN_SEGMENT_LENGTH 0.5
512
+    #define SCARA_MIN_SEGMENT_LENGTH 0.5f
513
   #endif
513
   #endif
514
 
514
 
515
   /**
515
   /**
566
 
566
 
567
     // For SCARA enforce a minimum segment size
567
     // For SCARA enforce a minimum segment size
568
     #if IS_SCARA
568
     #if IS_SCARA
569
-      NOMORE(segments, cartesian_mm * (1.0 / SCARA_MIN_SEGMENT_LENGTH));
569
+      NOMORE(segments, cartesian_mm * (1.0f / float(SCARA_MIN_SEGMENT_LENGTH)));
570
     #endif
570
     #endif
571
 
571
 
572
     // At least one segment is required
572
     // At least one segment is required
573
     NOLESS(segments, 1U);
573
     NOLESS(segments, 1U);
574
 
574
 
575
     // The approximate length of each segment
575
     // The approximate length of each segment
576
-    const float inv_segments = 1.0 / float(segments),
576
+    const float inv_segments = 1.0f / float(segments),
577
                 segment_distance[XYZE] = {
577
                 segment_distance[XYZE] = {
578
                   xdiff * inv_segments,
578
                   xdiff * inv_segments,
579
                   ydiff * inv_segments,
579
                   ydiff * inv_segments,
599
       // SCARA needs to scale the feed rate from mm/s to degrees/s
599
       // SCARA needs to scale the feed rate from mm/s to degrees/s
600
       // i.e., Complete the angular vector in the given time.
600
       // i.e., Complete the angular vector in the given time.
601
       const float segment_length = cartesian_mm * inv_segments,
601
       const float segment_length = cartesian_mm * inv_segments,
602
-                  inv_segment_length = 1.0 / segment_length, // 1/mm/segs
602
+                  inv_segment_length = 1.0f / segment_length, // 1/mm/segs
603
                   inverse_secs = inv_segment_length * _feedrate_mm_s;
603
                   inverse_secs = inv_segment_length * _feedrate_mm_s;
604
 
604
 
605
       float oldA = planner.position_float[A_AXIS],
605
       float oldA = planner.position_float[A_AXIS],
756
       NOLESS(segments, 1U);
756
       NOLESS(segments, 1U);
757
 
757
 
758
       // The approximate length of each segment
758
       // The approximate length of each segment
759
-      const float inv_segments = 1.0 / float(segments),
759
+      const float inv_segments = 1.0f / float(segments),
760
                   cartesian_segment_mm = cartesian_mm * inv_segments,
760
                   cartesian_segment_mm = cartesian_mm * inv_segments,
761
                   segment_distance[XYZE] = {
761
                   segment_distance[XYZE] = {
762
                     xdiff * inv_segments,
762
                     xdiff * inv_segments,
1335
   #if ENABLED(DEBUG_LEVELING_FEATURE)
1335
   #if ENABLED(DEBUG_LEVELING_FEATURE)
1336
     if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 1 Fast:");
1336
     if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 1 Fast:");
1337
   #endif
1337
   #endif
1338
-  do_homing_move(axis, 1.5 * max_length(axis) * axis_home_dir);
1338
+  do_homing_move(axis, 1.5f * max_length(axis) * axis_home_dir);
1339
 
1339
 
1340
   // When homing Z with probe respect probe clearance
1340
   // When homing Z with probe respect probe clearance
1341
   const float bump = axis_home_dir * (
1341
   const float bump = axis_home_dir * (

+ 10
- 10
Marlin/src/module/motion.h Просмотреть файл

71
  * Feedrate scaling and conversion
71
  * Feedrate scaling and conversion
72
  */
72
  */
73
 extern int16_t feedrate_percentage;
73
 extern int16_t feedrate_percentage;
74
-#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
74
+#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01f)
75
 
75
 
76
 extern uint8_t active_extruder;
76
 extern uint8_t active_extruder;
77
 
77
 
141
 void buffer_line_to_destination(const float fr_mm_s);
141
 void buffer_line_to_destination(const float fr_mm_s);
142
 
142
 
143
 #if IS_KINEMATIC
143
 #if IS_KINEMATIC
144
-  void prepare_uninterpolated_move_to_destination(const float fr_mm_s=0.0);
144
+  void prepare_uninterpolated_move_to_destination(const float fr_mm_s=0);
145
 #endif
145
 #endif
146
 
146
 
147
 void prepare_move_to_destination();
147
 void prepare_move_to_destination();
149
 /**
149
 /**
150
  * Blocking movement and shorthand functions
150
  * Blocking movement and shorthand functions
151
  */
151
  */
152
-void do_blocking_move_to(const float rx, const float ry, const float rz, const float &fr_mm_s=0.0);
153
-void do_blocking_move_to_x(const float &rx, const float &fr_mm_s=0.0);
154
-void do_blocking_move_to_z(const float &rz, const float &fr_mm_s=0.0);
155
-void do_blocking_move_to_xy(const float &rx, const float &ry, const float &fr_mm_s=0.0);
152
+void do_blocking_move_to(const float rx, const float ry, const float rz, const float &fr_mm_s=0);
153
+void do_blocking_move_to_x(const float &rx, const float &fr_mm_s=0);
154
+void do_blocking_move_to_z(const float &rz, const float &fr_mm_s=0);
155
+void do_blocking_move_to_xy(const float &rx, const float &ry, const float &fr_mm_s=0);
156
 
156
 
157
 void setup_for_endstop_or_probe_move();
157
 void setup_for_endstop_or_probe_move();
158
 void clean_up_after_endstop_or_probe_move();
158
 void clean_up_after_endstop_or_probe_move();
268
    // Return true if the given position is within the machine bounds.
268
    // Return true if the given position is within the machine bounds.
269
   inline bool position_is_reachable(const float &rx, const float &ry) {
269
   inline bool position_is_reachable(const float &rx, const float &ry) {
270
     // Add 0.001 margin to deal with float imprecision
270
     // Add 0.001 margin to deal with float imprecision
271
-    return WITHIN(rx, X_MIN_POS - 0.001, X_MAX_POS + 0.001)
272
-        && WITHIN(ry, Y_MIN_POS - 0.001, Y_MAX_POS + 0.001);
271
+    return WITHIN(rx, X_MIN_POS - 0.001f, X_MAX_POS + 0.001f)
272
+        && WITHIN(ry, Y_MIN_POS - 0.001f, Y_MAX_POS + 0.001f);
273
   }
273
   }
274
 
274
 
275
   #if HAS_BED_PROBE
275
   #if HAS_BED_PROBE
282
      */
282
      */
283
     inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
283
     inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
284
       return position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER))
284
       return position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER))
285
-          && WITHIN(rx, MIN_PROBE_X - 0.001, MAX_PROBE_X + 0.001)
286
-          && WITHIN(ry, MIN_PROBE_Y - 0.001, MAX_PROBE_Y + 0.001);
285
+          && WITHIN(rx, MIN_PROBE_X - 0.001f, MAX_PROBE_X + 0.001f)
286
+          && WITHIN(ry, MIN_PROBE_Y - 0.001f, MAX_PROBE_Y + 0.001f);
287
     }
287
     }
288
   #endif
288
   #endif
289
 
289
 

+ 30
- 30
Marlin/src/module/planner.cpp Просмотреть файл

150
 
150
 
151
 int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder
151
 int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder
152
 
152
 
153
-float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0); // The flow percentage and volumetric multiplier combine to scale E movement
153
+float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement
154
 
154
 
155
 #if DISABLED(NO_VOLUMETRICS)
155
 #if DISABLED(NO_VOLUMETRICS)
156
   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
156
   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
157
-        Planner::volumetric_area_nominal = CIRCLE_AREA((DEFAULT_NOMINAL_FILAMENT_DIA) * 0.5), // Nominal cross-sectional area
157
+        Planner::volumetric_area_nominal = CIRCLE_AREA((float(DEFAULT_NOMINAL_FILAMENT_DIA)) * 0.5f), // Nominal cross-sectional area
158
         Planner::volumetric_multiplier[EXTRUDERS];  // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner
158
         Planner::volumetric_multiplier[EXTRUDERS];  // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner
159
 #endif
159
 #endif
160
 
160
 
188
 #if ENABLED(AUTOTEMP)
188
 #if ENABLED(AUTOTEMP)
189
   float Planner::autotemp_max = 250,
189
   float Planner::autotemp_max = 250,
190
         Planner::autotemp_min = 210,
190
         Planner::autotemp_min = 210,
191
-        Planner::autotemp_factor = 0.1;
191
+        Planner::autotemp_factor = 0.1f;
192
   bool Planner::autotemp_enabled = false;
192
   bool Planner::autotemp_enabled = false;
193
 #endif
193
 #endif
194
 
194
 
236
     ZERO(position_float);
236
     ZERO(position_float);
237
   #endif
237
   #endif
238
   ZERO(previous_speed);
238
   ZERO(previous_speed);
239
-  previous_nominal_speed_sqr = 0.0;
239
+  previous_nominal_speed_sqr = 0;
240
   #if ABL_PLANAR
240
   #if ABL_PLANAR
241
     bed_level_matrix.set_to_identity();
241
     bed_level_matrix.set_to_identity();
242
   #endif
242
   #endif
859
 
859
 
860
       const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
860
       const float new_entry_speed_sqr = TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH)
861
         ? max_entry_speed_sqr
861
         ? max_entry_speed_sqr
862
-        : MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(MINIMUM_PLANNER_SPEED), current->millimeters));
862
+        : MIN(max_entry_speed_sqr, max_allowable_speed_sqr(-current->acceleration, next ? next->entry_speed_sqr : sq(float(MINIMUM_PLANNER_SPEED)), current->millimeters));
863
       if (current->entry_speed_sqr != new_entry_speed_sqr) {
863
       if (current->entry_speed_sqr != new_entry_speed_sqr) {
864
 
864
 
865
         // Need to recalculate the block speed - Mark it now, so the stepper
865
         // Need to recalculate the block speed - Mark it now, so the stepper
1076
 
1076
 
1077
             // NOTE: Entry and exit factors always > 0 by all previous logic operations.
1077
             // NOTE: Entry and exit factors always > 0 by all previous logic operations.
1078
             const float current_nominal_speed = SQRT(current->nominal_speed_sqr),
1078
             const float current_nominal_speed = SQRT(current->nominal_speed_sqr),
1079
-                        nomr = 1.0 / current_nominal_speed;
1079
+                        nomr = 1.0f / current_nominal_speed;
1080
             calculate_trapezoid_for_block(current, current_entry_speed * nomr, next_entry_speed * nomr);
1080
             calculate_trapezoid_for_block(current, current_entry_speed * nomr, next_entry_speed * nomr);
1081
             #if ENABLED(LIN_ADVANCE)
1081
             #if ENABLED(LIN_ADVANCE)
1082
               if (current->use_advance_lead) {
1082
               if (current->use_advance_lead) {
1115
       // Block is not BUSY, we won the race against the Stepper ISR:
1115
       // Block is not BUSY, we won the race against the Stepper ISR:
1116
 
1116
 
1117
       const float next_nominal_speed = SQRT(next->nominal_speed_sqr),
1117
       const float next_nominal_speed = SQRT(next->nominal_speed_sqr),
1118
-                  nomr = 1.0 / next_nominal_speed;
1119
-      calculate_trapezoid_for_block(next, next_entry_speed * nomr, (MINIMUM_PLANNER_SPEED) * nomr);
1118
+                  nomr = 1.0f / next_nominal_speed;
1119
+      calculate_trapezoid_for_block(next, next_entry_speed * nomr, float(MINIMUM_PLANNER_SPEED) * nomr);
1120
       #if ENABLED(LIN_ADVANCE)
1120
       #if ENABLED(LIN_ADVANCE)
1121
         if (next->use_advance_lead) {
1121
         if (next->use_advance_lead) {
1122
           const float comp = next->e_D_ratio * extruder_advance_K * axis_steps_per_mm[E_AXIS];
1122
           const float comp = next->e_D_ratio * extruder_advance_K * axis_steps_per_mm[E_AXIS];
1162
 
1162
 
1163
     float t = autotemp_min + high * autotemp_factor;
1163
     float t = autotemp_min + high * autotemp_factor;
1164
     t = constrain(t, autotemp_min, autotemp_max);
1164
     t = constrain(t, autotemp_min, autotemp_max);
1165
-    if (t < oldt) t = t * (1 - (AUTOTEMP_OLDWEIGHT)) + oldt * (AUTOTEMP_OLDWEIGHT);
1165
+    if (t < oldt) t = t * (1 - float(AUTOTEMP_OLDWEIGHT)) + oldt * float(AUTOTEMP_OLDWEIGHT);
1166
     oldt = t;
1166
     oldt = t;
1167
     thermalManager.setTargetHotend(t, 0);
1167
     thermalManager.setTargetHotend(t, 0);
1168
   }
1168
   }
1317
    * Return 1.0 with volumetric off or a diameter of 0.0.
1317
    * Return 1.0 with volumetric off or a diameter of 0.0.
1318
    */
1318
    */
1319
   inline float calculate_volumetric_multiplier(const float &diameter) {
1319
   inline float calculate_volumetric_multiplier(const float &diameter) {
1320
-    return (parser.volumetric_enabled && diameter) ? 1.0 / CIRCLE_AREA(diameter * 0.5) : 1.0;
1320
+    return (parser.volumetric_enabled && diameter) ? RECIPROCAL(CIRCLE_AREA(diameter * 0.5f)) : 1;
1321
   }
1321
   }
1322
 
1322
 
1323
   /**
1323
   /**
1341
    */
1341
    */
1342
   void Planner::calculate_volumetric_for_width_sensor(const int8_t encoded_ratio) {
1342
   void Planner::calculate_volumetric_for_width_sensor(const int8_t encoded_ratio) {
1343
     // Reconstitute the nominal/measured ratio
1343
     // Reconstitute the nominal/measured ratio
1344
-    const float nom_meas_ratio = 1.0 + 0.01 * encoded_ratio,
1344
+    const float nom_meas_ratio = 1 + 0.01f * encoded_ratio,
1345
                 ratio_2 = sq(nom_meas_ratio);
1345
                 ratio_2 = sq(nom_meas_ratio);
1346
 
1346
 
1347
     volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] = parser.volumetric_enabled
1347
     volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] = parser.volumetric_enabled
1348
-      ? ratio_2 / CIRCLE_AREA(filament_width_nominal * 0.5) // Volumetric uses a true volumetric multiplier
1348
+      ? ratio_2 / CIRCLE_AREA(filament_width_nominal * 0.5f) // Volumetric uses a true volumetric multiplier
1349
       : ratio_2;                                            // Linear squares the ratio, which scales the volume
1349
       : ratio_2;                                            // Linear squares the ratio, which scales the volume
1350
 
1350
 
1351
     refresh_e_factor(FILAMENT_SENSOR_EXTRUDER_NUM);
1351
     refresh_e_factor(FILAMENT_SENSOR_EXTRUDER_NUM);
1690
   if (de < 0) SBI(dm, E_AXIS);
1690
   if (de < 0) SBI(dm, E_AXIS);
1691
 
1691
 
1692
   const float esteps_float = de * e_factor[extruder];
1692
   const float esteps_float = de * e_factor[extruder];
1693
-  const uint32_t esteps = ABS(esteps_float) + 0.5;
1693
+  const uint32_t esteps = ABS(esteps_float) + 0.5f;
1694
 
1694
 
1695
   // Clear all flags, including the "busy" bit
1695
   // Clear all flags, including the "busy" bit
1696
   block->flag = 0x00;
1696
   block->flag = 0x00;
1957
   // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill
1957
   // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill
1958
   #if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT)
1958
   #if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT)
1959
     // Segment time im micro seconds
1959
     // Segment time im micro seconds
1960
-    uint32_t segment_time_us = LROUND(1000000.0 / inverse_secs);
1960
+    uint32_t segment_time_us = LROUND(1000000.0f / inverse_secs);
1961
   #endif
1961
   #endif
1962
 
1962
 
1963
   #if ENABLED(SLOWDOWN)
1963
   #if ENABLED(SLOWDOWN)
1965
       if (segment_time_us < min_segment_time_us) {
1965
       if (segment_time_us < min_segment_time_us) {
1966
         // buffer is draining, add extra time.  The amount of time added increases if the buffer is still emptied more.
1966
         // buffer is draining, add extra time.  The amount of time added increases if the buffer is still emptied more.
1967
         const uint32_t nst = segment_time_us + LROUND(2 * (min_segment_time_us - segment_time_us) / moves_queued);
1967
         const uint32_t nst = segment_time_us + LROUND(2 * (min_segment_time_us - segment_time_us) / moves_queued);
1968
-        inverse_secs = 1000000.0 / nst;
1968
+        inverse_secs = 1000000.0f / nst;
1969
         #if defined(XY_FREQUENCY_LIMIT) || ENABLED(ULTRA_LCD)
1969
         #if defined(XY_FREQUENCY_LIMIT) || ENABLED(ULTRA_LCD)
1970
           segment_time_us = nst;
1970
           segment_time_us = nst;
1971
         #endif
1971
         #endif
2005
         while (filwidth_delay_dist >= MMD_MM) filwidth_delay_dist -= MMD_MM;
2005
         while (filwidth_delay_dist >= MMD_MM) filwidth_delay_dist -= MMD_MM;
2006
 
2006
 
2007
         // Convert into an index into the measurement array
2007
         // Convert into an index into the measurement array
2008
-        filwidth_delay_index[0] = int8_t(filwidth_delay_dist * 0.1);
2008
+        filwidth_delay_index[0] = int8_t(filwidth_delay_dist * 0.1f);
2009
 
2009
 
2010
         // If the index has changed (must have gone forward)...
2010
         // If the index has changed (must have gone forward)...
2011
         if (filwidth_delay_index[0] != filwidth_delay_index[1]) {
2011
         if (filwidth_delay_index[0] != filwidth_delay_index[1]) {
2021
   #endif
2021
   #endif
2022
 
2022
 
2023
   // Calculate and limit speed in mm/sec for each axis
2023
   // Calculate and limit speed in mm/sec for each axis
2024
-  float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed
2024
+  float current_speed[NUM_AXIS], speed_factor = 1.0f; // factor <1 decreases speed
2025
   LOOP_XYZE(i) {
2025
   LOOP_XYZE(i) {
2026
     const float cs = ABS((current_speed[i] = delta_mm[i] * inverse_secs));
2026
     const float cs = ABS((current_speed[i] = delta_mm[i] * inverse_secs));
2027
     #if ENABLED(DISTINCT_E_FACTORS)
2027
     #if ENABLED(DISTINCT_E_FACTORS)
2069
   #endif // XY_FREQUENCY_LIMIT
2069
   #endif // XY_FREQUENCY_LIMIT
2070
 
2070
 
2071
   // Correct the speed
2071
   // Correct the speed
2072
-  if (speed_factor < 1.0) {
2072
+  if (speed_factor < 1.0f) {
2073
     LOOP_XYZE(i) current_speed[i] *= speed_factor;
2073
     LOOP_XYZE(i) current_speed[i] *= speed_factor;
2074
     block->nominal_rate *= speed_factor;
2074
     block->nominal_rate *= speed_factor;
2075
     block->nominal_speed_sqr = block->nominal_speed_sqr * sq(speed_factor);
2075
     block->nominal_speed_sqr = block->nominal_speed_sqr * sq(speed_factor);
2142
 
2142
 
2143
         // 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!
2143
         // 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!
2144
         // 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.
2144
         // 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.
2145
-        if (block->e_D_ratio > 3.0)
2145
+        if (block->e_D_ratio > 3.0f)
2146
           block->use_advance_lead = false;
2146
           block->use_advance_lead = false;
2147
         else {
2147
         else {
2148
           const uint32_t max_accel_steps_per_s2 = MAX_E_JERK / (extruder_advance_K * block->e_D_ratio) * steps_per_mm;
2148
           const uint32_t max_accel_steps_per_s2 = MAX_E_JERK / (extruder_advance_K * block->e_D_ratio) * steps_per_mm;
2177
   block->acceleration_steps_per_s2 = accel;
2177
   block->acceleration_steps_per_s2 = accel;
2178
   block->acceleration = accel / steps_per_mm;
2178
   block->acceleration = accel / steps_per_mm;
2179
   #if DISABLED(S_CURVE_ACCELERATION)
2179
   #if DISABLED(S_CURVE_ACCELERATION)
2180
-    block->acceleration_rate = (uint32_t)(accel * (4096.0 * 4096.0 / (STEPPER_TIMER_RATE)));
2180
+    block->acceleration_rate = (uint32_t)(accel * (4096.0f * 4096.0f / (STEPPER_TIMER_RATE)));
2181
   #endif
2181
   #endif
2182
   #if ENABLED(LIN_ADVANCE)
2182
   #if ENABLED(LIN_ADVANCE)
2183
     if (block->use_advance_lead) {
2183
     if (block->use_advance_lead) {
2250
                                 ;
2250
                                 ;
2251
 
2251
 
2252
       // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
2252
       // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
2253
-      if (junction_cos_theta > 0.999999) {
2253
+      if (junction_cos_theta > 0.999999f) {
2254
         // For a 0 degree acute junction, just set minimum junction speed.
2254
         // For a 0 degree acute junction, just set minimum junction speed.
2255
-        vmax_junction_sqr = sq(MINIMUM_PLANNER_SPEED);
2255
+        vmax_junction_sqr = sq(float(MINIMUM_PLANNER_SPEED));
2256
       }
2256
       }
2257
       else {
2257
       else {
2258
-        NOLESS(junction_cos_theta, -0.999999); // Check for numerical round-off to avoid divide by zero.
2258
+        NOLESS(junction_cos_theta, -0.999999f); // Check for numerical round-off to avoid divide by zero.
2259
 
2259
 
2260
         // Convert delta vector to unit vector
2260
         // Convert delta vector to unit vector
2261
         float junction_unit_vec[XYZE] = {
2261
         float junction_unit_vec[XYZE] = {
2267
         normalize_junction_vector(junction_unit_vec);
2267
         normalize_junction_vector(junction_unit_vec);
2268
 
2268
 
2269
         const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec),
2269
         const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec),
2270
-                    sin_theta_d2 = SQRT(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive.
2270
+                    sin_theta_d2 = SQRT(0.5f * (1.0f - junction_cos_theta)); // Trig half angle identity. Always positive.
2271
 
2271
 
2272
-        vmax_junction_sqr = (junction_acceleration * junction_deviation_mm * sin_theta_d2) / (1.0 - sin_theta_d2);
2273
-        if (block->millimeters < 1.0) {
2272
+        vmax_junction_sqr = (junction_acceleration * junction_deviation_mm * sin_theta_d2) / (1.0f - sin_theta_d2);
2273
+        if (block->millimeters < 1) {
2274
 
2274
 
2275
           // Fast acos approximation, minus the error bar to be safe
2275
           // Fast acos approximation, minus the error bar to be safe
2276
-          const float junction_theta = (RADIANS(-40) * sq(junction_cos_theta) - RADIANS(50)) * junction_cos_theta + RADIANS(90) - 0.18;
2276
+          const float junction_theta = (RADIANS(-40) * sq(junction_cos_theta) - RADIANS(50)) * junction_cos_theta + RADIANS(90) - 0.18f;
2277
 
2277
 
2278
           // If angle is greater than 135 degrees (octagon), find speed for approximate arc
2278
           // If angle is greater than 135 degrees (octagon), find speed for approximate arc
2279
           if (junction_theta > RADIANS(135)) {
2279
           if (junction_theta > RADIANS(135)) {
2287
       vmax_junction_sqr = MIN3(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr);
2287
       vmax_junction_sqr = MIN3(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr);
2288
     }
2288
     }
2289
     else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later.
2289
     else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later.
2290
-      vmax_junction_sqr = 0.0;
2290
+      vmax_junction_sqr = 0;
2291
 
2291
 
2292
     COPY(previous_unit_vec, unit_vec);
2292
     COPY(previous_unit_vec, unit_vec);
2293
 
2293
 
2378
   block->max_entry_speed_sqr = vmax_junction_sqr;
2378
   block->max_entry_speed_sqr = vmax_junction_sqr;
2379
 
2379
 
2380
   // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED.
2380
   // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED.
2381
-  const float v_allowable_sqr = max_allowable_speed_sqr(-block->acceleration, sq(MINIMUM_PLANNER_SPEED), block->millimeters);
2381
+  const float v_allowable_sqr = max_allowable_speed_sqr(-block->acceleration, sq(float(MINIMUM_PLANNER_SPEED)), block->millimeters);
2382
 
2382
 
2383
   // If we are trying to add a split block, start with the
2383
   // If we are trying to add a split block, start with the
2384
   // max. allowed speed to avoid an interrupted first move.
2384
   // max. allowed speed to avoid an interrupted first move.
2385
-  block->entry_speed_sqr = !split_move ? sq(MINIMUM_PLANNER_SPEED) : MIN(vmax_junction_sqr, v_allowable_sqr);
2385
+  block->entry_speed_sqr = !split_move ? sq(float(MINIMUM_PLANNER_SPEED)) : MIN(vmax_junction_sqr, v_allowable_sqr);
2386
 
2386
 
2387
   // Initialize planner efficiency flags
2387
   // Initialize planner efficiency flags
2388
   // Set flag if block will always reach maximum junction speed regardless of entry/exit speeds.
2388
   // Set flag if block will always reach maximum junction speed regardless of entry/exit speeds.

+ 9
- 9
Marlin/src/module/planner.h Просмотреть файл

324
     static void refresh_positioning();
324
     static void refresh_positioning();
325
 
325
 
326
     FORCE_INLINE static void refresh_e_factor(const uint8_t e) {
326
     FORCE_INLINE static void refresh_e_factor(const uint8_t e) {
327
-      e_factor[e] = (flow_percentage[e] * 0.01
327
+      e_factor[e] = (flow_percentage[e] * 0.01f
328
         #if DISABLED(NO_VOLUMETRICS)
328
         #if DISABLED(NO_VOLUMETRICS)
329
           * volumetric_multiplier[e]
329
           * volumetric_multiplier[e]
330
         #endif
330
         #endif
362
        *  Returns 0.0 if Z is past the specified 'Fade Height'.
362
        *  Returns 0.0 if Z is past the specified 'Fade Height'.
363
        */
363
        */
364
       inline static float fade_scaling_factor_for_z(const float &rz) {
364
       inline static float fade_scaling_factor_for_z(const float &rz) {
365
-        static float z_fade_factor = 1.0;
365
+        static float z_fade_factor = 1;
366
         if (z_fade_height) {
366
         if (z_fade_height) {
367
-          if (rz >= z_fade_height) return 0.0;
367
+          if (rz >= z_fade_height) return 0;
368
           if (last_fade_z != rz) {
368
           if (last_fade_z != rz) {
369
             last_fade_z = rz;
369
             last_fade_z = rz;
370
-            z_fade_factor = 1.0 - rz * inverse_z_fade_height;
370
+            z_fade_factor = 1 - rz * inverse_z_fade_height;
371
           }
371
           }
372
           return z_fade_factor;
372
           return z_fade_factor;
373
         }
373
         }
374
-        return 1.0;
374
+        return 1;
375
       }
375
       }
376
 
376
 
377
-      FORCE_INLINE static void force_fade_recalc() { last_fade_z = -999.999; }
377
+      FORCE_INLINE static void force_fade_recalc() { last_fade_z = -999.999f; }
378
 
378
 
379
       FORCE_INLINE static void set_z_fade_height(const float &zfh) {
379
       FORCE_INLINE static void set_z_fade_height(const float &zfh) {
380
         z_fade_height = zfh > 0 ? zfh : 0;
380
         z_fade_height = zfh > 0 ? zfh : 0;
390
 
390
 
391
       FORCE_INLINE static float fade_scaling_factor_for_z(const float &rz) {
391
       FORCE_INLINE static float fade_scaling_factor_for_z(const float &rz) {
392
         UNUSED(rz);
392
         UNUSED(rz);
393
-        return 1.0;
393
+        return 1;
394
       }
394
       }
395
 
395
 
396
       FORCE_INLINE static bool leveling_active_at_z(const float &rz) { UNUSED(rz); return true; }
396
       FORCE_INLINE static bool leveling_active_at_z(const float &rz) { UNUSED(rz); return true; }
831
     #if ENABLED(JUNCTION_DEVIATION)
831
     #if ENABLED(JUNCTION_DEVIATION)
832
 
832
 
833
       FORCE_INLINE static void normalize_junction_vector(float (&vector)[XYZE]) {
833
       FORCE_INLINE static void normalize_junction_vector(float (&vector)[XYZE]) {
834
-        float magnitude_sq = 0.0;
834
+        float magnitude_sq = 0;
835
         LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]);
835
         LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]);
836
-        const float inv_magnitude = 1.0 / SQRT(magnitude_sq);
836
+        const float inv_magnitude = RSQRT(magnitude_sq);
837
         LOOP_XYZE(idx) vector[idx] *= inv_magnitude;
837
         LOOP_XYZE(idx) vector[idx] *= inv_magnitude;
838
       }
838
       }
839
 
839
 

+ 14
- 14
Marlin/src/module/planner_bezier.cpp Просмотреть файл

40
 #include "../gcode/queue.h"
40
 #include "../gcode/queue.h"
41
 
41
 
42
 // See the meaning in the documentation of cubic_b_spline().
42
 // See the meaning in the documentation of cubic_b_spline().
43
-#define MIN_STEP 0.002
44
-#define MAX_STEP 0.1
45
-#define SIGMA 0.1
43
+#define MIN_STEP 0.002f
44
+#define MAX_STEP 0.1f
45
+#define SIGMA 0.1f
46
 
46
 
47
 // Compute the linear interpolation between two real numbers.
47
 // Compute the linear interpolation between two real numbers.
48
-inline static float interp(float a, float b, float t) { return (1.0 - t) * a + t * b; }
48
+inline static float interp(float a, float b, float t) { return (1 - t) * a + t * b; }
49
 
49
 
50
 /**
50
 /**
51
  * Compute a Bézier curve using the De Casteljau's algorithm (see
51
  * Compute a Bézier curve using the De Casteljau's algorithm (see
114
               first1 = position[Y_AXIS] + offset[1],
114
               first1 = position[Y_AXIS] + offset[1],
115
               second0 = target[X_AXIS] + offset[2],
115
               second0 = target[X_AXIS] + offset[2],
116
               second1 = target[Y_AXIS] + offset[3];
116
               second1 = target[Y_AXIS] + offset[3];
117
-  float t = 0.0;
117
+  float t = 0;
118
 
118
 
119
   float bez_target[4];
119
   float bez_target[4];
120
   bez_target[X_AXIS] = position[X_AXIS];
120
   bez_target[X_AXIS] = position[X_AXIS];
123
 
123
 
124
   millis_t next_idle_ms = millis() + 200UL;
124
   millis_t next_idle_ms = millis() + 200UL;
125
 
125
 
126
-  while (t < 1.0) {
126
+  while (t < 1) {
127
 
127
 
128
     thermalManager.manage_heater();
128
     thermalManager.manage_heater();
129
     millis_t now = millis();
129
     millis_t now = millis();
136
     // close to a linear interpolation.
136
     // close to a linear interpolation.
137
     bool did_reduce = false;
137
     bool did_reduce = false;
138
     float new_t = t + step;
138
     float new_t = t + step;
139
-    NOMORE(new_t, 1.0);
139
+    NOMORE(new_t, 1);
140
     float new_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], new_t),
140
     float new_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], new_t),
141
           new_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], new_t);
141
           new_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], new_t);
142
     for (;;) {
142
     for (;;) {
143
       if (new_t - t < (MIN_STEP)) break;
143
       if (new_t - t < (MIN_STEP)) break;
144
-      const float candidate_t = 0.5 * (t + new_t),
144
+      const float candidate_t = 0.5f * (t + new_t),
145
                   candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
145
                   candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
146
                   candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
146
                   candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
147
-                  interp_pos0 = 0.5 * (bez_target[X_AXIS] + new_pos0),
148
-                  interp_pos1 = 0.5 * (bez_target[Y_AXIS] + new_pos1);
147
+                  interp_pos0 = 0.5f * (bez_target[X_AXIS] + new_pos0),
148
+                  interp_pos1 = 0.5f * (bez_target[Y_AXIS] + new_pos1);
149
       if (dist1(candidate_pos0, candidate_pos1, interp_pos0, interp_pos1) <= (SIGMA)) break;
149
       if (dist1(candidate_pos0, candidate_pos1, interp_pos0, interp_pos1) <= (SIGMA)) break;
150
       new_t = candidate_t;
150
       new_t = candidate_t;
151
       new_pos0 = candidate_pos0;
151
       new_pos0 = candidate_pos0;
156
     // If we did not reduce the step, maybe we should enlarge it.
156
     // If we did not reduce the step, maybe we should enlarge it.
157
     if (!did_reduce) for (;;) {
157
     if (!did_reduce) for (;;) {
158
       if (new_t - t > MAX_STEP) break;
158
       if (new_t - t > MAX_STEP) break;
159
-      const float candidate_t = t + 2.0 * (new_t - t);
160
-      if (candidate_t >= 1.0) break;
159
+      const float candidate_t = t + 2 * (new_t - t);
160
+      if (candidate_t >= 1) break;
161
       const float candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
161
       const float candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
162
                   candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
162
                   candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
163
-                  interp_pos0 = 0.5 * (bez_target[X_AXIS] + candidate_pos0),
164
-                  interp_pos1 = 0.5 * (bez_target[Y_AXIS] + candidate_pos1);
163
+                  interp_pos0 = 0.5f * (bez_target[X_AXIS] + candidate_pos0),
164
+                  interp_pos1 = 0.5f * (bez_target[Y_AXIS] + candidate_pos1);
165
       if (dist1(new_pos0, new_pos1, interp_pos0, interp_pos1) > (SIGMA)) break;
165
       if (dist1(new_pos0, new_pos1, interp_pos0, interp_pos1) > (SIGMA)) break;
166
       new_t = candidate_t;
166
       new_t = candidate_t;
167
       new_pos0 = candidate_pos0;
167
       new_pos0 = candidate_pos0;

+ 1
- 1
Marlin/src/module/printcounter.cpp Просмотреть файл

53
   return lastDuration - tmp;
53
   return lastDuration - tmp;
54
 }
54
 }
55
 
55
 
56
-void PrintCounter::incFilamentUsed(double const &amount) {
56
+void PrintCounter::incFilamentUsed(float const &amount) {
57
   #if ENABLED(DEBUG_PRINTCOUNTER)
57
   #if ENABLED(DEBUG_PRINTCOUNTER)
58
     debug(PSTR("incFilamentUsed"));
58
     debug(PSTR("incFilamentUsed"));
59
   #endif
59
   #endif

+ 3
- 3
Marlin/src/module/printcounter.h Просмотреть файл

37
   #define STATS_EEPROM_ADDRESS 0x32
37
   #define STATS_EEPROM_ADDRESS 0x32
38
 #endif
38
 #endif
39
 
39
 
40
-struct printStatistics {    // 16 bytes (20 with real doubles)
40
+struct printStatistics {    // 16 bytes
41
   //const uint8_t magic;    // Magic header, it will always be 0x16
41
   //const uint8_t magic;    // Magic header, it will always be 0x16
42
   uint16_t totalPrints;     // Number of prints
42
   uint16_t totalPrints;     // Number of prints
43
   uint16_t finishedPrints;  // Number of complete prints
43
   uint16_t finishedPrints;  // Number of complete prints
44
   uint32_t printTime;       // Accumulated printing time
44
   uint32_t printTime;       // Accumulated printing time
45
   uint32_t longestPrint;    // Longest successful print job
45
   uint32_t longestPrint;    // Longest successful print job
46
-  double   filamentUsed;    // Accumulated filament consumed in mm
46
+  float    filamentUsed;    // Accumulated filament consumed in mm
47
 };
47
 };
48
 
48
 
49
 class PrintCounter: public Stopwatch {
49
 class PrintCounter: public Stopwatch {
128
      *
128
      *
129
      * @param amount The amount of filament used in mm
129
      * @param amount The amount of filament used in mm
130
      */
130
      */
131
-    static void incFilamentUsed(double const &amount);
131
+    static void incFilamentUsed(float const &amount);
132
 
132
 
133
     /**
133
     /**
134
      * @brief Reset the Print Statistics
134
      * @brief Reset the Print Statistics

+ 1
- 1
Marlin/src/module/probe.cpp Просмотреть файл

625
   #if MULTIPLE_PROBING > 2
625
   #if MULTIPLE_PROBING > 2
626
 
626
 
627
     // Return the average value of all probes
627
     // Return the average value of all probes
628
-    const float measured_z = probes_total * (1.0 / (MULTIPLE_PROBING));
628
+    const float measured_z = probes_total * (1.0f / (MULTIPLE_PROBING));
629
 
629
 
630
   #elif MULTIPLE_PROBING == 2
630
   #elif MULTIPLE_PROBING == 2
631
 
631
 

+ 7
- 7
Marlin/src/module/temperature.cpp Просмотреть файл

393
               SERIAL_PROTOCOLPAIR(MSG_T_MIN, min);
393
               SERIAL_PROTOCOLPAIR(MSG_T_MIN, min);
394
               SERIAL_PROTOCOLPAIR(MSG_T_MAX, max);
394
               SERIAL_PROTOCOLPAIR(MSG_T_MAX, max);
395
               if (cycles > 2) {
395
               if (cycles > 2) {
396
-                Ku = (4.0 * d) / (M_PI * (max - min) * 0.5);
397
-                Tu = ((float)(t_low + t_high) * 0.001);
396
+                Ku = (4.0f * d) / (float(M_PI) * (max - min) * 0.5f);
397
+                Tu = ((float)(t_low + t_high) * 0.001f);
398
                 SERIAL_PROTOCOLPAIR(MSG_KU, Ku);
398
                 SERIAL_PROTOCOLPAIR(MSG_KU, Ku);
399
                 SERIAL_PROTOCOLPAIR(MSG_TU, Tu);
399
                 SERIAL_PROTOCOLPAIR(MSG_TU, Tu);
400
-                workKp = 0.6 * Ku;
400
+                workKp = 0.6f * Ku;
401
                 workKi = 2 * workKp / Tu;
401
                 workKi = 2 * workKp / Tu;
402
-                workKd = workKp * Tu * 0.125;
402
+                workKd = workKp * Tu * 0.125f;
403
                 SERIAL_PROTOCOLLNPGM("\n" MSG_CLASSIC_PID);
403
                 SERIAL_PROTOCOLLNPGM("\n" MSG_CLASSIC_PID);
404
                 SERIAL_PROTOCOLPAIR(MSG_KP, workKp);
404
                 SERIAL_PROTOCOLPAIR(MSG_KP, workKp);
405
                 SERIAL_PROTOCOLPAIR(MSG_KI, workKi);
405
                 SERIAL_PROTOCOLPAIR(MSG_KI, workKi);
644
   #if ENABLED(PIDTEMP)
644
   #if ENABLED(PIDTEMP)
645
     #if DISABLED(PID_OPENLOOP)
645
     #if DISABLED(PID_OPENLOOP)
646
       pid_error[HOTEND_INDEX] = target_temperature[HOTEND_INDEX] - current_temperature[HOTEND_INDEX];
646
       pid_error[HOTEND_INDEX] = target_temperature[HOTEND_INDEX] - current_temperature[HOTEND_INDEX];
647
-      dTerm[HOTEND_INDEX] = PID_K2 * PID_PARAM(Kd, HOTEND_INDEX) * (current_temperature[HOTEND_INDEX] - temp_dState[HOTEND_INDEX]) + PID_K1 * dTerm[HOTEND_INDEX];
647
+      dTerm[HOTEND_INDEX] = PID_K2 * PID_PARAM(Kd, HOTEND_INDEX) * (current_temperature[HOTEND_INDEX] - temp_dState[HOTEND_INDEX]) + float(PID_K1) * dTerm[HOTEND_INDEX];
648
       temp_dState[HOTEND_INDEX] = current_temperature[HOTEND_INDEX];
648
       temp_dState[HOTEND_INDEX] = current_temperature[HOTEND_INDEX];
649
       #if HEATER_IDLE_HANDLER
649
       #if HEATER_IDLE_HANDLER
650
         if (heater_idle_timeout_exceeded[HOTEND_INDEX]) {
650
         if (heater_idle_timeout_exceeded[HOTEND_INDEX]) {
1098
 
1098
 
1099
   // Convert raw Filament Width to millimeters
1099
   // Convert raw Filament Width to millimeters
1100
   float Temperature::analog2widthFil() {
1100
   float Temperature::analog2widthFil() {
1101
-    return current_raw_filwidth * 5.0 * (1.0 / 16383.0);
1101
+    return current_raw_filwidth * 5.0f * (1.0f / 16383.0f);
1102
   }
1102
   }
1103
 
1103
 
1104
   /**
1104
   /**
1111
    */
1111
    */
1112
   int8_t Temperature::widthFil_to_size_ratio() {
1112
   int8_t Temperature::widthFil_to_size_ratio() {
1113
     if (ABS(filament_width_nominal - filament_width_meas) <= FILWIDTH_ERROR_MARGIN)
1113
     if (ABS(filament_width_nominal - filament_width_meas) <= FILWIDTH_ERROR_MARGIN)
1114
-      return int(100.0 * filament_width_nominal / filament_width_meas) - 100;
1114
+      return int(100.0f * filament_width_nominal / filament_width_meas) - 100;
1115
     return 0;
1115
     return 0;
1116
   }
1116
   }
1117
 
1117
 

+ 5
- 5
Marlin/src/module/temperature.h Просмотреть файл

100
 #define ACTUAL_ADC_SAMPLES MAX(int(MIN_ADC_ISR_LOOPS), int(SensorsReady))
100
 #define ACTUAL_ADC_SAMPLES MAX(int(MIN_ADC_ISR_LOOPS), int(SensorsReady))
101
 
101
 
102
 #if HAS_PID_HEATING
102
 #if HAS_PID_HEATING
103
-  #define PID_K2 (1.0-PID_K1)
103
+  #define PID_K2 (1-float(PID_K1))
104
   #define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / TEMP_TIMER_FREQUENCY)
104
   #define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / TEMP_TIMER_FREQUENCY)
105
 
105
 
106
   // Apply the scale factors to the PID values
106
   // Apply the scale factors to the PID values
107
-  #define scalePID_i(i)   ( (i) * PID_dT )
108
-  #define unscalePID_i(i) ( (i) / PID_dT )
109
-  #define scalePID_d(d)   ( (d) / PID_dT )
110
-  #define unscalePID_d(d) ( (d) * PID_dT )
107
+  #define scalePID_i(i)   ( float(i) * PID_dT )
108
+  #define unscalePID_i(i) ( float(i) / PID_dT )
109
+  #define scalePID_d(d)   ( float(d) / PID_dT )
110
+  #define unscalePID_d(d) ( float(d) * PID_dT )
111
 #endif
111
 #endif
112
 
112
 
113
 class Temperature {
113
 class Temperature {

Загрузка…
Отмена
Сохранить