Преглед на файлове

Apply maths macros and type changes ahead of HAL

Scott Lahteine преди 8 години
родител
ревизия
6c45d0fd81

+ 1
- 1
Marlin/G26_Mesh_Validation_Tool.cpp Целия файл

600
 
600
 
601
     // If the end point of the line is closer to the nozzle, flip the direction,
601
     // If the end point of the line is closer to the nozzle, flip the direction,
602
     // moving from the end to the start. On very small lines the optimization isn't worth it.
602
     // moving from the end to the start. On very small lines the optimization isn't worth it.
603
-    if (dist_end < dist_start && (SIZE_OF_INTERSECTION_CIRCLES) < abs(line_length)) {
603
+    if (dist_end < dist_start && (SIZE_OF_INTERSECTION_CIRCLES) < FABS(line_length)) {
604
       return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz);
604
       return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz);
605
     }
605
     }
606
 
606
 

+ 22
- 19
Marlin/I2CPositionEncoder.cpp Целия файл

126
     }
126
     }
127
 
127
 
128
     lastPosition = position;
128
     lastPosition = position;
129
-    unsigned long positionTime = millis();
129
+    millis_t positionTime = millis();
130
 
130
 
131
     //only do error correction if setup and enabled
131
     //only do error correction if setup and enabled
132
     if (ec && ecMethod != I2CPE_ECM_NONE) {
132
     if (ec && ecMethod != I2CPE_ECM_NONE) {
133
 
133
 
134
       #if defined(I2CPE_EC_THRESH_PROPORTIONAL)
134
       #if defined(I2CPE_EC_THRESH_PROPORTIONAL)
135
+        millis_t deltaTime = positionTime - lastPositionTime;
135
         unsigned long distance = abs(position - lastPosition);
136
         unsigned long distance = abs(position - lastPosition);
136
-        unsigned long deltaTime = positionTime - lastPositionTime;
137
         unsigned long speed = distance / deltaTime;
137
         unsigned long speed = distance / deltaTime;
138
-        float threshold = constrain((speed / 50), 1, 50) * ecThreshold;
138
+        float threshold = constrain(speed / 50, 1, 50) * ecThreshold;
139
       #else
139
       #else
140
         float threshold = get_error_correct_threshold();
140
         float threshold = get_error_correct_threshold();
141
       #endif
141
       #endif
162
       //SERIAL_ECHOLN(error);
162
       //SERIAL_ECHOLN(error);
163
 
163
 
164
       #if defined(I2CPE_ERR_THRESH_ABORT)
164
       #if defined(I2CPE_ERR_THRESH_ABORT)
165
-        if (abs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) {
165
+        if (labs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) {
166
           //kill("Significant Error");
166
           //kill("Significant Error");
167
           SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!");
167
           SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!");
168
           SERIAL_ECHOLN(error);
168
           SERIAL_ECHOLN(error);
174
         if (errIdx == 0) {
174
         if (errIdx == 0) {
175
           // in order to correct for "error" but avoid correcting for noise and non skips
175
           // in order to correct for "error" but avoid correcting for noise and non skips
176
           // it must be > threshold and have a difference average of < 10 and be < 2000 steps
176
           // it must be > threshold and have a difference average of < 10 and be < 2000 steps
177
-          if (abs(error) > threshold * planner.axis_steps_per_mm[encoderAxis] &&
178
-              diffSum < 10*(I2CPE_ERR_ARRAY_SIZE-1) && abs(error) < 2000) { //Check for persistent error (skip)
177
+          if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis] &&
178
+              diffSum < 10 * (I2CPE_ERR_ARRAY_SIZE - 1) && labs(error) < 2000) { //Check for persistent error (skip)
179
             SERIAL_ECHO(axis_codes[encoderAxis]);
179
             SERIAL_ECHO(axis_codes[encoderAxis]);
180
-            SERIAL_ECHOPAIR(" diffSum: ", diffSum/(I2CPE_ERR_ARRAY_SIZE-1));
180
+            SERIAL_ECHOPAIR(" diffSum: ", diffSum / (I2CPE_ERR_ARRAY_SIZE - 1));
181
             SERIAL_ECHOPAIR(" - err detected: ", error / planner.axis_steps_per_mm[encoderAxis]);
181
             SERIAL_ECHOPAIR(" - err detected: ", error / planner.axis_steps_per_mm[encoderAxis]);
182
             SERIAL_ECHOLNPGM("mm; correcting!");
182
             SERIAL_ECHOLNPGM("mm; correcting!");
183
-            thermalManager.babystepsTodo[encoderAxis] = -lround(error);
183
+            thermalManager.babystepsTodo[encoderAxis] = -LROUND(error);
184
           }
184
           }
185
         }
185
         }
186
       #else
186
       #else
187
-        if (abs(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) {
187
+        if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) {
188
           //SERIAL_ECHOLN(error);
188
           //SERIAL_ECHOLN(error);
189
           //SERIAL_ECHOLN(position);
189
           //SERIAL_ECHOLN(position);
190
-          thermalManager.babystepsTodo[encoderAxis] = -lround(error/2);
190
+          thermalManager.babystepsTodo[encoderAxis] = -LROUND(error/2);
191
         }
191
         }
192
       #endif
192
       #endif
193
 
193
 
194
-      if (abs(error) > (I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) && millis() - lastErrorCountTime > I2CPE_ERR_CNT_DEBOUNCE_MS) {
195
-        SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]);
196
-        SERIAL_ECHOPAIR(" axis. error: ", (int)error);
197
-        SERIAL_ECHOLNPAIR("; diffSum: ", diffSum);
198
-        errorCount++;
199
-        lastErrorCountTime = millis();
194
+      if (labs(error) > I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) {
195
+        const millis_t ms = millis();
196
+        if (ELAPSED(ms, nextErrorCountTime)) {
197
+          SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]);
198
+          SERIAL_ECHOPAIR(" axis. error: ", (int)error);
199
+          SERIAL_ECHOLNPAIR("; diffSum: ", diffSum);
200
+          errorCount++;
201
+          nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS;
202
+        }
200
       }
203
       }
201
     }
204
     }
202
 
205
 
255
     actual = mm_from_count(position);
258
     actual = mm_from_count(position);
256
     error = actual - target;
259
     error = actual - target;
257
 
260
 
258
-    if (abs(error) > 10000) error = 0; // ?
261
+    if (labs(error) > 10000) error = 0; // ?
259
 
262
 
260
     if (report) {
263
     if (report) {
261
       SERIAL_ECHO(axis_codes[encoderAxis]);
264
       SERIAL_ECHO(axis_codes[encoderAxis]);
284
     stepperTicksPerUnit = (type == I2CPE_ENC_TYPE_ROTARY) ? stepperTicks : planner.axis_steps_per_mm[encoderAxis];
287
     stepperTicksPerUnit = (type == I2CPE_ENC_TYPE_ROTARY) ? stepperTicks : planner.axis_steps_per_mm[encoderAxis];
285
 
288
 
286
     //convert both 'ticks' into same units / base
289
     //convert both 'ticks' into same units / base
287
-    encoderCountInStepperTicksScaled = lround((stepperTicksPerUnit * encoderTicks) / encoderTicksPerUnit);
290
+    encoderCountInStepperTicksScaled = LROUND((stepperTicksPerUnit * encoderTicks) / encoderTicksPerUnit);
288
 
291
 
289
     long target = stepper.position(encoderAxis),
292
     long target = stepper.position(encoderAxis),
290
          error = (encoderCountInStepperTicksScaled - target);
293
          error = (encoderCountInStepperTicksScaled - target);
291
 
294
 
292
     //suppress discontinuities (might be caused by bad I2C readings...?)
295
     //suppress discontinuities (might be caused by bad I2C readings...?)
293
-    bool suppressOutput = (abs(error - errorPrev) > 100);
296
+    bool suppressOutput = (labs(error - errorPrev) > 100);
294
 
297
 
295
     if (report) {
298
     if (report) {
296
       SERIAL_ECHO(axis_codes[encoderAxis]);
299
       SERIAL_ECHO(axis_codes[encoderAxis]);

+ 1
- 1
Marlin/I2CPositionEncoder.h Целия файл

136
                     position;
136
                     position;
137
 
137
 
138
     unsigned long   lastPositionTime        = 0,
138
     unsigned long   lastPositionTime        = 0,
139
-                    lastErrorCountTime      = 0,
139
+                    nextErrorCountTime      = 0,
140
                     lastErrorTime;
140
                     lastErrorTime;
141
 
141
 
142
     //double        positionMm; //calculate
142
     //double        positionMm; //calculate

+ 2
- 2
Marlin/Marlin.h Целия файл

210
 /**
210
 /**
211
  * Feedrate scaling and conversion
211
  * Feedrate scaling and conversion
212
  */
212
  */
213
-extern int feedrate_percentage;
213
+extern int16_t feedrate_percentage;
214
 
214
 
215
 #define MMM_TO_MMS(MM_M) ((MM_M)/60.0)
215
 #define MMM_TO_MMS(MM_M) ((MM_M)/60.0)
216
 #define MMS_TO_MMM(MM_S) ((MM_S)*60.0)
216
 #define MMS_TO_MMM(MM_S) ((MM_S)*60.0)
218
 
218
 
219
 extern bool axis_relative_modes[];
219
 extern bool axis_relative_modes[];
220
 extern bool volumetric_enabled;
220
 extern bool volumetric_enabled;
221
-extern int flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder
221
+extern int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder
222
 extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
222
 extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
223
 extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
223
 extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
224
 extern bool axis_known_position[XYZ];
224
 extern bool axis_known_position[XYZ];

+ 31
- 31
Marlin/Marlin_main.cpp Целия файл

421
 
421
 
422
 float feedrate_mm_s = MMM_TO_MMS(1500.0);
422
 float feedrate_mm_s = MMM_TO_MMS(1500.0);
423
 static float saved_feedrate_mm_s;
423
 static float saved_feedrate_mm_s;
424
-int feedrate_percentage = 100, saved_feedrate_percentage,
424
+int16_t feedrate_percentage = 100, saved_feedrate_percentage,
425
     flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100);
425
     flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100);
426
 
426
 
427
 bool axis_relative_modes[] = AXIS_RELATIVE_MODES,
427
 bool axis_relative_modes[] = AXIS_RELATIVE_MODES,
2968
 
2968
 
2969
   #if ENABLED(Z_DUAL_ENDSTOPS)
2969
   #if ENABLED(Z_DUAL_ENDSTOPS)
2970
     if (axis == Z_AXIS) {
2970
     if (axis == Z_AXIS) {
2971
-      float adj = fabs(z_endstop_adj);
2971
+      float adj = FABS(z_endstop_adj);
2972
       bool lockZ1;
2972
       bool lockZ1;
2973
       if (axis_home_dir > 0) {
2973
       if (axis_home_dir > 0) {
2974
         adj = -adj;
2974
         adj = -adj;
3293
           const float e = clockwise ^ (r < 0) ? -1 : 1,           // clockwise -1/1, counterclockwise 1/-1
3293
           const float e = clockwise ^ (r < 0) ? -1 : 1,           // clockwise -1/1, counterclockwise 1/-1
3294
                       dx = x2 - x1, dy = y2 - y1,                 // X and Y differences
3294
                       dx = x2 - x1, dy = y2 - y1,                 // X and Y differences
3295
                       d = HYPOT(dx, dy),                          // Linear distance between the points
3295
                       d = HYPOT(dx, dy),                          // Linear distance between the points
3296
-                      h = sqrt(sq(r) - sq(d * 0.5)),              // Distance to the arc pivot-point
3296
+                      h = SQRT(sq(r) - sq(d * 0.5)),              // Distance to the arc pivot-point
3297
                       mx = (x1 + x2) * 0.5, my = (y1 + y2) * 0.5, // Point between the two points
3297
                       mx = (x1 + x2) * 0.5, my = (y1 + y2) * 0.5, // Point between the two points
3298
                       sx = -dy / d, sy = dx / d,                  // Slope of the perpendicular bisector
3298
                       sx = -dy / d, sy = dx / d,                  // Slope of the perpendicular bisector
3299
                       cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc
3299
                       cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc
3448
     const float mlx = max_length(X_AXIS),
3448
     const float mlx = max_length(X_AXIS),
3449
                 mly = max_length(Y_AXIS),
3449
                 mly = max_length(Y_AXIS),
3450
                 mlratio = mlx > mly ? mly / mlx : mlx / mly,
3450
                 mlratio = mlx > mly ? mly / mlx : mlx / mly,
3451
-                fr_mm_s = min(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * sqrt(sq(mlratio) + 1.0);
3451
+                fr_mm_s = min(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0);
3452
 
3452
 
3453
     do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_s);
3453
     do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_s);
3454
     endstops.hit_on_purpose(); // clear endstop hit flags
3454
     endstops.hit_on_purpose(); // clear endstop hit flags
4605
           const float xBase = xCount * xGridSpacing + left_probe_bed_position,
4605
           const float xBase = xCount * xGridSpacing + left_probe_bed_position,
4606
                       yBase = yCount * yGridSpacing + front_probe_bed_position;
4606
                       yBase = yCount * yGridSpacing + front_probe_bed_position;
4607
 
4607
 
4608
-          xProbe = floor(xBase + (xBase < 0 ? 0 : 0.5));
4609
-          yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5));
4608
+          xProbe = FLOOR(xBase + (xBase < 0 ? 0 : 0.5));
4609
+          yProbe = FLOOR(yBase + (yBase < 0 ? 0 : 0.5));
4610
 
4610
 
4611
           #if ENABLED(AUTO_BED_LEVELING_LINEAR)
4611
           #if ENABLED(AUTO_BED_LEVELING_LINEAR)
4612
             indexIntoAB[xCount][yCount] = abl_probe_index;
4612
             indexIntoAB[xCount][yCount] = abl_probe_index;
4710
             float xBase = left_probe_bed_position + xGridSpacing * xCount,
4710
             float xBase = left_probe_bed_position + xGridSpacing * xCount,
4711
                   yBase = front_probe_bed_position + yGridSpacing * yCount;
4711
                   yBase = front_probe_bed_position + yGridSpacing * yCount;
4712
 
4712
 
4713
-            xProbe = floor(xBase + (xBase < 0 ? 0 : 0.5));
4714
-            yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5));
4713
+            xProbe = FLOOR(xBase + (xBase < 0 ? 0 : 0.5));
4714
+            yProbe = FLOOR(yBase + (yBase < 0 ? 0 : 0.5));
4715
 
4715
 
4716
             #if ENABLED(AUTO_BED_LEVELING_LINEAR)
4716
             #if ENABLED(AUTO_BED_LEVELING_LINEAR)
4717
               indexIntoAB[xCount][yCount] = ++abl_probe_index; // 0...
4717
               indexIntoAB[xCount][yCount] = ++abl_probe_index; // 0...
5263
             N++;
5263
             N++;
5264
           }
5264
           }
5265
         zero_std_dev_old = zero_std_dev;
5265
         zero_std_dev_old = zero_std_dev;
5266
-        zero_std_dev = round(sqrt(S2 / N) * 1000.0) / 1000.0 + 0.00001;
5266
+        zero_std_dev = round(SQRT(S2 / N) * 1000.0) / 1000.0 + 0.00001;
5267
 
5267
 
5268
         if (iterations == 1) home_offset[Z_AXIS] = zh_old; // reset height after 1st probe change
5268
         if (iterations == 1) home_offset[Z_AXIS] = zh_old; // reset height after 1st probe change
5269
 
5269
 
5464
     float retract_mm[XYZ];
5464
     float retract_mm[XYZ];
5465
     LOOP_XYZ(i) {
5465
     LOOP_XYZ(i) {
5466
       float dist = destination[i] - current_position[i];
5466
       float dist = destination[i] - current_position[i];
5467
-      retract_mm[i] = fabs(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1);
5467
+      retract_mm[i] = FABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1);
5468
     }
5468
     }
5469
 
5469
 
5470
     stepper.synchronize();  // wait until the machine is idle
5470
     stepper.synchronize();  // wait until the machine is idle
5528
 
5528
 
5529
     // If any axis has enough movement, do the move
5529
     // If any axis has enough movement, do the move
5530
     LOOP_XYZ(i)
5530
     LOOP_XYZ(i)
5531
-      if (fabs(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) {
5531
+      if (FABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) {
5532
         if (!parser.seen('F')) feedrate_mm_s = homing_feedrate(i);
5532
         if (!parser.seen('F')) feedrate_mm_s = homing_feedrate(i);
5533
         // If G38.2 fails throw an error
5533
         // If G38.2 fails throw an error
5534
         if (!G38_run_probe() && is_38_2) {
5534
         if (!G38_run_probe() && is_38_2) {
6851
       for (uint8_t j = 0; j <= n; j++)
6851
       for (uint8_t j = 0; j <= n; j++)
6852
         sum += sq(sample_set[j] - mean);
6852
         sum += sq(sample_set[j] - mean);
6853
 
6853
 
6854
-      sigma = sqrt(sum / (n + 1));
6854
+      sigma = SQRT(sum / (n + 1));
6855
       if (verbose_level > 0) {
6855
       if (verbose_level > 0) {
6856
         if (verbose_level > 1) {
6856
         if (verbose_level > 1) {
6857
           SERIAL_PROTOCOL(n + 1);
6857
           SERIAL_PROTOCOL(n + 1);
7266
 
7266
 
7267
     #if TEMP_RESIDENCY_TIME > 0
7267
     #if TEMP_RESIDENCY_TIME > 0
7268
 
7268
 
7269
-      const float temp_diff = fabs(target_temp - temp);
7269
+      const float temp_diff = FABS(target_temp - temp);
7270
 
7270
 
7271
       if (!residency_start_ms) {
7271
       if (!residency_start_ms) {
7272
         // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time.
7272
         // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time.
7395
 
7395
 
7396
       #if TEMP_BED_RESIDENCY_TIME > 0
7396
       #if TEMP_BED_RESIDENCY_TIME > 0
7397
 
7397
 
7398
-        const float temp_diff = fabs(target_temp - temp);
7398
+        const float temp_diff = FABS(target_temp - temp);
7399
 
7399
 
7400
         if (!residency_start_ms) {
7400
         if (!residency_start_ms) {
7401
           // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time.
7401
           // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time.
9252
 
9252
 
9253
       #if ENABLED(BABYSTEP_ZPROBE_OFFSET)
9253
       #if ENABLED(BABYSTEP_ZPROBE_OFFSET)
9254
         if (!no_babystep && leveling_is_active())
9254
         if (!no_babystep && leveling_is_active())
9255
-          thermalManager.babystep_axis(Z_AXIS, -lround(diff * planner.axis_steps_per_mm[Z_AXIS]));
9255
+          thermalManager.babystep_axis(Z_AXIS, -LROUND(diff * planner.axis_steps_per_mm[Z_AXIS]));
9256
       #else
9256
       #else
9257
         UNUSED(no_babystep);
9257
         UNUSED(no_babystep);
9258
       #endif
9258
       #endif
11171
     if (last_x != x) {
11171
     if (last_x != x) {
11172
       last_x = x;
11172
       last_x = x;
11173
       ratio_x = x * ABL_BG_FACTOR(X_AXIS);
11173
       ratio_x = x * ABL_BG_FACTOR(X_AXIS);
11174
-      const float gx = constrain(floor(ratio_x), 0, ABL_BG_POINTS_X - FAR_EDGE_OR_BOX);
11174
+      const float gx = constrain(FLOOR(ratio_x), 0, ABL_BG_POINTS_X - FAR_EDGE_OR_BOX);
11175
       ratio_x -= gx;      // Subtract whole to get the ratio within the grid box
11175
       ratio_x -= gx;      // Subtract whole to get the ratio within the grid box
11176
 
11176
 
11177
       #if DISABLED(EXTRAPOLATE_BEYOND_GRID)
11177
       #if DISABLED(EXTRAPOLATE_BEYOND_GRID)
11188
       if (last_y != y) {
11188
       if (last_y != y) {
11189
         last_y = y;
11189
         last_y = y;
11190
         ratio_y = y * ABL_BG_FACTOR(Y_AXIS);
11190
         ratio_y = y * ABL_BG_FACTOR(Y_AXIS);
11191
-        const float gy = constrain(floor(ratio_y), 0, ABL_BG_POINTS_Y - FAR_EDGE_OR_BOX);
11191
+        const float gy = constrain(FLOOR(ratio_y), 0, ABL_BG_POINTS_Y - FAR_EDGE_OR_BOX);
11192
         ratio_y -= gy;
11192
         ratio_y -= gy;
11193
 
11193
 
11194
         #if DISABLED(EXTRAPOLATE_BEYOND_GRID)
11194
         #if DISABLED(EXTRAPOLATE_BEYOND_GRID)
11221
 
11221
 
11222
     /*
11222
     /*
11223
     static float last_offset = 0;
11223
     static float last_offset = 0;
11224
-    if (fabs(last_offset - offset) > 0.2) {
11224
+    if (FABS(last_offset - offset) > 0.2) {
11225
       SERIAL_ECHOPGM("Sudden Shift at ");
11225
       SERIAL_ECHOPGM("Sudden Shift at ");
11226
       SERIAL_ECHOPAIR("x=", x);
11226
       SERIAL_ECHOPAIR("x=", x);
11227
       SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]);
11227
       SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]);
11290
 
11290
 
11291
   #else
11291
   #else
11292
 
11292
 
11293
-    #define _SQRT(n) sqrt(n)
11293
+    #define _SQRT(n) SQRT(n)
11294
 
11294
 
11295
   #endif
11295
   #endif
11296
 
11296
 
11364
     float distance = delta[A_AXIS];
11364
     float distance = delta[A_AXIS];
11365
     cartesian[Y_AXIS] = LOGICAL_Y_POSITION(DELTA_PRINTABLE_RADIUS);
11365
     cartesian[Y_AXIS] = LOGICAL_Y_POSITION(DELTA_PRINTABLE_RADIUS);
11366
     inverse_kinematics(cartesian);
11366
     inverse_kinematics(cartesian);
11367
-    return abs(distance - delta[A_AXIS]);
11367
+    return FABS(distance - delta[A_AXIS]);
11368
   }
11368
   }
11369
 
11369
 
11370
   /**
11370
   /**
11397
     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 };
11397
     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 };
11398
 
11398
 
11399
     // Get the Magnitude of vector.
11399
     // Get the Magnitude of vector.
11400
-    float d = sqrt( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) );
11400
+    float d = SQRT( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) );
11401
 
11401
 
11402
     // Create unit vector by dividing by magnitude.
11402
     // Create unit vector by dividing by magnitude.
11403
     float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d };
11403
     float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d };
11416
     float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
11416
     float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
11417
 
11417
 
11418
     // The magnitude of Y component
11418
     // The magnitude of Y component
11419
-    float j = sqrt( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) );
11419
+    float j = SQRT( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) );
11420
 
11420
 
11421
     // Convert to a unit vector
11421
     // Convert to a unit vector
11422
     ey[0] /= j; ey[1] /= j;  ey[2] /= j;
11422
     ey[0] /= j; ey[1] /= j;  ey[2] /= j;
11433
     // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
11433
     // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
11434
     float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + sq(d)) / (d * 2),
11434
     float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + sq(d)) / (d * 2),
11435
           Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + HYPOT2(i, j)) / 2 - i * Xnew) / j,
11435
           Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + HYPOT2(i, j)) / 2 - i * Xnew) / j,
11436
-          Znew = sqrt(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew));
11436
+          Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew));
11437
 
11437
 
11438
     // Start from the origin of the old coordinates and add vectors in the
11438
     // Start from the origin of the old coordinates and add vectors in the
11439
     // old coords that represent the Xnew, Ynew and Znew to find the point
11439
     // old coords that represent the Xnew, Ynew and Znew to find the point
11656
     };
11656
     };
11657
 
11657
 
11658
     // Get the linear distance in XYZ
11658
     // Get the linear distance in XYZ
11659
-    float cartesian_mm = sqrt(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS]));
11659
+    float cartesian_mm = SQRT(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS]));
11660
 
11660
 
11661
     // If the move is very short, check the E move distance
11661
     // If the move is very short, check the E move distance
11662
-    if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = abs(difference[E_AXIS]);
11662
+    if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = FABS(difference[E_AXIS]);
11663
 
11663
 
11664
     // No E move either? Game over.
11664
     // No E move either? Game over.
11665
     if (UNEAR_ZERO(cartesian_mm)) return true;
11665
     if (UNEAR_ZERO(cartesian_mm)) return true;
11947
                 extruder_travel = logical[E_AXIS] - current_position[E_AXIS];
11947
                 extruder_travel = logical[E_AXIS] - current_position[E_AXIS];
11948
 
11948
 
11949
     // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required.
11949
     // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required.
11950
-    float angular_travel = atan2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y);
11950
+    float angular_travel = ATAN2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y);
11951
     if (angular_travel < 0) angular_travel += RADIANS(360);
11951
     if (angular_travel < 0) angular_travel += RADIANS(360);
11952
     if (clockwise) angular_travel -= RADIANS(360);
11952
     if (clockwise) angular_travel -= RADIANS(360);
11953
 
11953
 
11955
     if (angular_travel == 0 && current_position[X_AXIS] == logical[X_AXIS] && current_position[Y_AXIS] == logical[Y_AXIS])
11955
     if (angular_travel == 0 && current_position[X_AXIS] == logical[X_AXIS] && current_position[Y_AXIS] == logical[Y_AXIS])
11956
       angular_travel += RADIANS(360);
11956
       angular_travel += RADIANS(360);
11957
 
11957
 
11958
-    const float mm_of_travel = HYPOT(angular_travel * radius, fabs(linear_travel));
11958
+    const float mm_of_travel = HYPOT(angular_travel * radius, FABS(linear_travel));
11959
     if (mm_of_travel < 0.001) return;
11959
     if (mm_of_travel < 0.001) return;
11960
 
11960
 
11961
-    uint16_t segments = floor(mm_of_travel / (MM_PER_ARC_SEGMENT));
11961
+    uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT));
11962
     if (segments == 0) segments = 1;
11962
     if (segments == 0) segments = 1;
11963
 
11963
 
11964
     /**
11964
     /**
12155
     else
12155
     else
12156
       C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2);
12156
       C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2);
12157
 
12157
 
12158
-    S2 = sqrt(1 - sq(C2));
12158
+    S2 = SQRT(1 - sq(C2));
12159
 
12159
 
12160
     // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
12160
     // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
12161
     SK1 = L1 + L2 * C2;
12161
     SK1 = L1 + L2 * C2;
12164
     SK2 = L2 * S2;
12164
     SK2 = L2 * S2;
12165
 
12165
 
12166
     // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
12166
     // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
12167
-    THETA = atan2(SK1, SK2) - atan2(sx, sy);
12167
+    THETA = ATAN2(SK1, SK2) - ATAN2(sx, sy);
12168
 
12168
 
12169
     // Angle of Arm2
12169
     // Angle of Arm2
12170
-    PSI = atan2(S2, C2);
12170
+    PSI = ATAN2(S2, C2);
12171
 
12171
 
12172
     delta[A_AXIS] = DEGREES(THETA);        // theta is support arm angle
12172
     delta[A_AXIS] = DEGREES(THETA);        // theta is support arm angle
12173
     delta[B_AXIS] = DEGREES(THETA + PSI);  // equal to sub arm angle (inverted motor)
12173
     delta[B_AXIS] = DEGREES(THETA + PSI);  // equal to sub arm angle (inverted motor)

+ 1
- 1
Marlin/digipot_mcp4018.cpp Целия файл

44
 #define DIGIPOT_A4988_MAX_CURRENT       (DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax) - 0.5)
44
 #define DIGIPOT_A4988_MAX_CURRENT       (DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax) - 0.5)
45
 
45
 
46
 static byte current_to_wiper(const float current) {
46
 static byte current_to_wiper(const float current) {
47
-  return byte(ceil(float(DIGIPOT_A4988_FACTOR) * current));
47
+  return byte(CEIL(float(DIGIPOT_A4988_FACTOR) * current));
48
 }
48
 }
49
 
49
 
50
 const uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = {
50
 const uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = {

+ 1
- 1
Marlin/digipot_mcp4451.cpp Целия файл

38
 #endif
38
 #endif
39
 
39
 
40
 static byte current_to_wiper(const float current) {
40
 static byte current_to_wiper(const float current) {
41
-  return byte(ceil(float((DIGIPOT_I2C_FACTOR * current))));
41
+  return byte(CEIL(float((DIGIPOT_I2C_FACTOR * current))));
42
 }
42
 }
43
 
43
 
44
 static void i2c_send(const byte addr, const byte a, const byte b) {
44
 static void i2c_send(const byte addr, const byte a, const byte b) {

+ 1
- 1
Marlin/gcode.h Целия файл

213
           linear_unit_factor = 1.0;
213
           linear_unit_factor = 1.0;
214
           break;
214
           break;
215
       }
215
       }
216
-      volumetric_unit_factor = pow(linear_unit_factor, 3.0);
216
+      volumetric_unit_factor = POW(linear_unit_factor, 3.0);
217
     }
217
     }
218
 
218
 
219
     inline static float axis_unit_factor(const AxisEnum axis) {
219
     inline static float axis_unit_factor(const AxisEnum axis) {

+ 1
- 1
Marlin/least_squares_fit.cpp Целия файл

59
   lsf->xzbar = lsf->xzbar / N - lsf->xbar * lsf->zbar;
59
   lsf->xzbar = lsf->xzbar / N - lsf->xbar * lsf->zbar;
60
   const float DD = lsf->x2bar * lsf->y2bar - sq(lsf->xybar);
60
   const float DD = lsf->x2bar * lsf->y2bar - sq(lsf->xybar);
61
 
61
 
62
-  if (fabs(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy))
62
+  if (FABS(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy))
63
     return 1;
63
     return 1;
64
 
64
 
65
   lsf->A = (lsf->yzbar * lsf->xybar - lsf->xzbar * lsf->y2bar) / DD;
65
   lsf->A = (lsf->yzbar * lsf->xybar - lsf->xzbar * lsf->y2bar) / DD;

+ 4
- 4
Marlin/least_squares_fit.h Целия файл

65
   lsf->xzbar += w * x * z;
65
   lsf->xzbar += w * x * z;
66
   lsf->yzbar += w * y * z;
66
   lsf->yzbar += w * y * z;
67
   lsf->N     += w;
67
   lsf->N     += w;
68
-  lsf->max_absx = max(fabs(w * x), lsf->max_absx);
69
-  lsf->max_absy = max(fabs(w * y), lsf->max_absy);
68
+  lsf->max_absx = max(FABS(w * x), lsf->max_absx);
69
+  lsf->max_absy = max(FABS(w * y), lsf->max_absy);
70
 }
70
 }
71
 
71
 
72
 void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) {
72
 void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) {
79
   lsf->xybar += x * y;
79
   lsf->xybar += x * y;
80
   lsf->xzbar += x * z;
80
   lsf->xzbar += x * z;
81
   lsf->yzbar += y * z;
81
   lsf->yzbar += y * z;
82
-  lsf->max_absx = max(fabs(x), lsf->max_absx);
83
-  lsf->max_absy = max(fabs(y), lsf->max_absy);
82
+  lsf->max_absx = max(FABS(x), lsf->max_absx);
83
+  lsf->max_absy = max(FABS(y), lsf->max_absy);
84
   lsf->N += 1.0;
84
   lsf->N += 1.0;
85
 }
85
 }
86
 
86
 

+ 14
- 2
Marlin/macros.h Целия файл

106
 #define RADIANS(d) ((d)*M_PI/180.0)
106
 #define RADIANS(d) ((d)*M_PI/180.0)
107
 #define DEGREES(r) ((r)*180.0/M_PI)
107
 #define DEGREES(r) ((r)*180.0/M_PI)
108
 #define HYPOT2(x,y) (sq(x)+sq(y))
108
 #define HYPOT2(x,y) (sq(x)+sq(y))
109
-#define HYPOT(x,y) sqrt(HYPOT2(x,y))
110
 
109
 
111
 #define SIGN(a) ((a>0)-(a<0))
110
 #define SIGN(a) ((a>0)-(a<0))
112
 
111
 
193
 #define RECIPROCAL(x) (NEAR_ZERO(x) ? 0.0 : 1.0 / (x))
192
 #define RECIPROCAL(x) (NEAR_ZERO(x) ? 0.0 : 1.0 / (x))
194
 #define FIXFLOAT(f) (f + 0.00001)
193
 #define FIXFLOAT(f) (f + 0.00001)
195
 
194
 
196
-#endif // __MACROS_H
195
+//
196
+// Maths macros that can be overridden by HAL
197
+//
198
+#define ATAN2(y, x) atan2(y, x)
199
+#define FABS(x)     fabs(x)
200
+#define POW(x, y)   pow(x, y)
201
+#define SQRT(x)     sqrt(x)
202
+#define CEIL(x)     ceil(x)
203
+#define FLOOR(x)    floor(x)
204
+#define LROUND(x)   lround(x)
205
+#define FMOD(x, y)  fmod(x, y)
206
+#define HYPOT(x,y)  SQRT(HYPOT2(x,y))
207
+
208
+#endif //__MACROS_H

+ 4
- 4
Marlin/nozzle.cpp Целия файл

80
 
80
 
81
     for (uint8_t j = 0; j < strokes; j++) {
81
     for (uint8_t j = 0; j < strokes; j++) {
82
       for (uint8_t i = 0; i < (objects << 1); i++) {
82
       for (uint8_t i = 0; i < (objects << 1); i++) {
83
-        float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) );
84
-        float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) );
83
+        float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) );
84
+        float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) );
85
 
85
 
86
         do_blocking_move_to_xy(x, y);
86
         do_blocking_move_to_xy(x, y);
87
         if (i == 0) do_blocking_move_to_z(start.z);
87
         if (i == 0) do_blocking_move_to_z(start.z);
88
       }
88
       }
89
 
89
 
90
       for (int i = (objects << 1); i > -1; i--) {
90
       for (int i = (objects << 1); i > -1; i--) {
91
-        float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) );
92
-        float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) );
91
+        float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) );
92
+        float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) );
93
 
93
 
94
         do_blocking_move_to_xy(x, y);
94
         do_blocking_move_to_xy(x, y);
95
       }
95
       }

+ 2
- 2
Marlin/nozzle.h Целия файл

29
 #if ENABLED(NOZZLE_CLEAN_FEATURE)
29
 #if ENABLED(NOZZLE_CLEAN_FEATURE)
30
   constexpr float nozzle_clean_start_point[4] = NOZZLE_CLEAN_START_POINT,
30
   constexpr float nozzle_clean_start_point[4] = NOZZLE_CLEAN_START_POINT,
31
                   nozzle_clean_end_point[4] = NOZZLE_CLEAN_END_POINT,
31
                   nozzle_clean_end_point[4] = NOZZLE_CLEAN_END_POINT,
32
-                  nozzle_clean_length = fabs(nozzle_clean_start_point[X_AXIS] - nozzle_clean_end_point[X_AXIS]), //abs x size of wipe pad
33
-                  nozzle_clean_height = fabs(nozzle_clean_start_point[Y_AXIS] - nozzle_clean_end_point[Y_AXIS]); //abs y size of wipe pad
32
+                  nozzle_clean_length = FABS(nozzle_clean_start_point[X_AXIS] - nozzle_clean_end_point[X_AXIS]), //abs x size of wipe pad
33
+                  nozzle_clean_height = FABS(nozzle_clean_start_point[Y_AXIS] - nozzle_clean_end_point[Y_AXIS]); //abs y size of wipe pad
34
   constexpr bool nozzle_clean_horizontal = nozzle_clean_length >= nozzle_clean_height; //whether to zig-zag horizontally or vertically
34
   constexpr bool nozzle_clean_horizontal = nozzle_clean_length >= nozzle_clean_height; //whether to zig-zag horizontally or vertically
35
 #endif // NOZZLE_CLEAN_FEATURE
35
 #endif // NOZZLE_CLEAN_FEATURE
36
 
36
 

+ 32
- 32
Marlin/planner.cpp Целия файл

178
  * by the provided factors.
178
  * by the provided factors.
179
  */
179
  */
180
 void Planner::calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor) {
180
 void Planner::calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor) {
181
-  uint32_t initial_rate = ceil(block->nominal_rate * entry_factor),
182
-           final_rate = ceil(block->nominal_rate * exit_factor); // (steps per second)
181
+  uint32_t initial_rate = CEIL(block->nominal_rate * entry_factor),
182
+           final_rate = CEIL(block->nominal_rate * exit_factor); // (steps per second)
183
 
183
 
184
   // Limit minimal step rate (Otherwise the timer will overflow.)
184
   // Limit minimal step rate (Otherwise the timer will overflow.)
185
   NOLESS(initial_rate, MINIMAL_STEP_RATE);
185
   NOLESS(initial_rate, MINIMAL_STEP_RATE);
186
   NOLESS(final_rate, MINIMAL_STEP_RATE);
186
   NOLESS(final_rate, MINIMAL_STEP_RATE);
187
 
187
 
188
   int32_t accel = block->acceleration_steps_per_s2,
188
   int32_t accel = block->acceleration_steps_per_s2,
189
-          accelerate_steps = ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, accel)),
190
-          decelerate_steps = floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -accel)),
189
+          accelerate_steps = CEIL(estimate_acceleration_distance(initial_rate, block->nominal_rate, accel)),
190
+          decelerate_steps = FLOOR(estimate_acceleration_distance(block->nominal_rate, final_rate, -accel)),
191
           plateau_steps = block->step_event_count - accelerate_steps - decelerate_steps;
191
           plateau_steps = block->step_event_count - accelerate_steps - decelerate_steps;
192
 
192
 
193
   // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
193
   // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
194
   // have to use intersection_distance() to calculate when to abort accel and start braking
194
   // have to use intersection_distance() to calculate when to abort accel and start braking
195
   // in order to reach the final_rate exactly at the end of this block.
195
   // in order to reach the final_rate exactly at the end of this block.
196
   if (plateau_steps < 0) {
196
   if (plateau_steps < 0) {
197
-    accelerate_steps = ceil(intersection_distance(initial_rate, final_rate, accel, block->step_event_count));
197
+    accelerate_steps = CEIL(intersection_distance(initial_rate, final_rate, accel, block->step_event_count));
198
     NOLESS(accelerate_steps, 0); // Check limits due to numerical round-off
198
     NOLESS(accelerate_steps, 0); // Check limits due to numerical round-off
199
     accelerate_steps = min((uint32_t)accelerate_steps, block->step_event_count);//(We can cast here to unsigned, because the above line ensures that we are above zero)
199
     accelerate_steps = min((uint32_t)accelerate_steps, block->step_event_count);//(We can cast here to unsigned, because the above line ensures that we are above zero)
200
     plateau_steps = 0;
200
     plateau_steps = 0;
221
 // This method will calculate the junction jerk as the euclidean distance between the nominal
221
 // This method will calculate the junction jerk as the euclidean distance between the nominal
222
 // velocities of the respective blocks.
222
 // velocities of the respective blocks.
223
 //inline float junction_jerk(block_t *before, block_t *after) {
223
 //inline float junction_jerk(block_t *before, block_t *after) {
224
-//  return sqrt(
225
-//    pow((before->speed_x-after->speed_x), 2)+pow((before->speed_y-after->speed_y), 2));
224
+//  return SQRT(
225
+//    POW((before->speed_x-after->speed_x), 2)+POW((before->speed_y-after->speed_y), 2));
226
 //}
226
 //}
227
 
227
 
228
 
228
 
693
   // Calculate target position in absolute steps
693
   // Calculate target position in absolute steps
694
   //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow
694
   //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow
695
   const long target[XYZE] = {
695
   const long target[XYZE] = {
696
-    lround(a * axis_steps_per_mm[X_AXIS]),
697
-    lround(b * axis_steps_per_mm[Y_AXIS]),
698
-    lround(c * axis_steps_per_mm[Z_AXIS]),
699
-    lround(e * axis_steps_per_mm[E_AXIS_N])
696
+    LROUND(a * axis_steps_per_mm[X_AXIS]),
697
+    LROUND(b * axis_steps_per_mm[Y_AXIS]),
698
+    LROUND(c * axis_steps_per_mm[Z_AXIS]),
699
+    LROUND(e * axis_steps_per_mm[E_AXIS_N])
700
   };
700
   };
701
 
701
 
702
   // When changing extruders recalculate steps corresponding to the E position
702
   // When changing extruders recalculate steps corresponding to the E position
703
   #if ENABLED(DISTINCT_E_FACTORS)
703
   #if ENABLED(DISTINCT_E_FACTORS)
704
     if (last_extruder != extruder && axis_steps_per_mm[E_AXIS_N] != axis_steps_per_mm[E_AXIS + last_extruder]) {
704
     if (last_extruder != extruder && axis_steps_per_mm[E_AXIS_N] != axis_steps_per_mm[E_AXIS + last_extruder]) {
705
-      position[E_AXIS] = lround(position[E_AXIS] * axis_steps_per_mm[E_AXIS_N] * steps_to_mm[E_AXIS + last_extruder]);
705
+      position[E_AXIS] = LROUND(position[E_AXIS] * axis_steps_per_mm[E_AXIS_N] * steps_to_mm[E_AXIS + last_extruder]);
706
       last_extruder = extruder;
706
       last_extruder = extruder;
707
     }
707
     }
708
   #endif
708
   #endif
709
 
709
 
710
   #if ENABLED(LIN_ADVANCE)
710
   #if ENABLED(LIN_ADVANCE)
711
-    const float mm_D_float = sqrt(sq(a - position_float[X_AXIS]) + sq(b - position_float[Y_AXIS]));
711
+    const float mm_D_float = SQRT(sq(a - position_float[X_AXIS]) + sq(b - position_float[Y_AXIS]));
712
   #endif
712
   #endif
713
 
713
 
714
   const long da = target[X_AXIS] - position[X_AXIS],
714
   const long da = target[X_AXIS] - position[X_AXIS],
1036
   delta_mm[E_AXIS] = esteps_float * steps_to_mm[E_AXIS_N];
1036
   delta_mm[E_AXIS] = esteps_float * steps_to_mm[E_AXIS_N];
1037
 
1037
 
1038
   if (block->steps[X_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Y_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Z_AXIS] < MIN_STEPS_PER_SEGMENT) {
1038
   if (block->steps[X_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Y_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Z_AXIS] < MIN_STEPS_PER_SEGMENT) {
1039
-    block->millimeters = fabs(delta_mm[E_AXIS]);
1039
+    block->millimeters = FABS(delta_mm[E_AXIS]);
1040
   }
1040
   }
1041
   else {
1041
   else {
1042
-    block->millimeters = sqrt(
1042
+    block->millimeters = SQRT(
1043
       #if CORE_IS_XY
1043
       #if CORE_IS_XY
1044
         sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_AXIS])
1044
         sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_AXIS])
1045
       #elif CORE_IS_XZ
1045
       #elif CORE_IS_XZ
1061
   // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill
1061
   // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill
1062
   #if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT)
1062
   #if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT)
1063
     // Segment time im micro seconds
1063
     // Segment time im micro seconds
1064
-    unsigned long segment_time = lround(1000000.0 / inverse_mm_s);
1064
+    unsigned long segment_time = LROUND(1000000.0 / inverse_mm_s);
1065
   #endif
1065
   #endif
1066
   #if ENABLED(SLOWDOWN)
1066
   #if ENABLED(SLOWDOWN)
1067
     if (WITHIN(moves_queued, 2, (BLOCK_BUFFER_SIZE) / 2 - 1)) {
1067
     if (WITHIN(moves_queued, 2, (BLOCK_BUFFER_SIZE) / 2 - 1)) {
1068
       if (segment_time < min_segment_time) {
1068
       if (segment_time < min_segment_time) {
1069
         // buffer is draining, add extra time.  The amount of time added increases if the buffer is still emptied more.
1069
         // buffer is draining, add extra time.  The amount of time added increases if the buffer is still emptied more.
1070
-        inverse_mm_s = 1000000.0 / (segment_time + lround(2 * (min_segment_time - segment_time) / moves_queued));
1070
+        inverse_mm_s = 1000000.0 / (segment_time + LROUND(2 * (min_segment_time - segment_time) / moves_queued));
1071
         #if defined(XY_FREQUENCY_LIMIT) || ENABLED(ULTRA_LCD)
1071
         #if defined(XY_FREQUENCY_LIMIT) || ENABLED(ULTRA_LCD)
1072
-          segment_time = lround(1000000.0 / inverse_mm_s);
1072
+          segment_time = LROUND(1000000.0 / inverse_mm_s);
1073
         #endif
1073
         #endif
1074
       }
1074
       }
1075
     }
1075
     }
1082
   #endif
1082
   #endif
1083
 
1083
 
1084
   block->nominal_speed = block->millimeters * inverse_mm_s; // (mm/sec) Always > 0
1084
   block->nominal_speed = block->millimeters * inverse_mm_s; // (mm/sec) Always > 0
1085
-  block->nominal_rate = ceil(block->step_event_count * inverse_mm_s); // (step/sec) Always > 0
1085
+  block->nominal_rate = CEIL(block->step_event_count * inverse_mm_s); // (step/sec) Always > 0
1086
 
1086
 
1087
   #if ENABLED(FILAMENT_WIDTH_SENSOR)
1087
   #if ENABLED(FILAMENT_WIDTH_SENSOR)
1088
     static float filwidth_e_count = 0, filwidth_delay_dist = 0;
1088
     static float filwidth_e_count = 0, filwidth_delay_dist = 0;
1121
   // Calculate and limit speed in mm/sec for each axis
1121
   // Calculate and limit speed in mm/sec for each axis
1122
   float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed
1122
   float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed
1123
   LOOP_XYZE(i) {
1123
   LOOP_XYZE(i) {
1124
-    const float cs = fabs(current_speed[i] = delta_mm[i] * inverse_mm_s);
1124
+    const float cs = FABS(current_speed[i] = delta_mm[i] * inverse_mm_s);
1125
     #if ENABLED(DISTINCT_E_FACTORS)
1125
     #if ENABLED(DISTINCT_E_FACTORS)
1126
       if (i == E_AXIS) i += extruder;
1126
       if (i == E_AXIS) i += extruder;
1127
     #endif
1127
     #endif
1134
     // Check and limit the xy direction change frequency
1134
     // Check and limit the xy direction change frequency
1135
     const unsigned char direction_change = block->direction_bits ^ old_direction_bits;
1135
     const unsigned char direction_change = block->direction_bits ^ old_direction_bits;
1136
     old_direction_bits = block->direction_bits;
1136
     old_direction_bits = block->direction_bits;
1137
-    segment_time = lround((float)segment_time / speed_factor);
1137
+    segment_time = LROUND((float)segment_time / speed_factor);
1138
 
1138
 
1139
     long xs0 = axis_segment_time[X_AXIS][0],
1139
     long xs0 = axis_segment_time[X_AXIS][0],
1140
          xs1 = axis_segment_time[X_AXIS][1],
1140
          xs1 = axis_segment_time[X_AXIS][1],
1178
   uint32_t accel;
1178
   uint32_t accel;
1179
   if (!block->steps[X_AXIS] && !block->steps[Y_AXIS] && !block->steps[Z_AXIS]) {
1179
   if (!block->steps[X_AXIS] && !block->steps[Y_AXIS] && !block->steps[Z_AXIS]) {
1180
     // convert to: acceleration steps/sec^2
1180
     // convert to: acceleration steps/sec^2
1181
-    accel = ceil(retract_acceleration * steps_per_mm);
1181
+    accel = CEIL(retract_acceleration * steps_per_mm);
1182
   }
1182
   }
1183
   else {
1183
   else {
1184
     #define LIMIT_ACCEL_LONG(AXIS,INDX) do{ \
1184
     #define LIMIT_ACCEL_LONG(AXIS,INDX) do{ \
1196
     }while(0)
1196
     }while(0)
1197
 
1197
 
1198
     // Start with print or travel acceleration
1198
     // Start with print or travel acceleration
1199
-    accel = ceil((esteps ? acceleration : travel_acceleration) * steps_per_mm);
1199
+    accel = CEIL((esteps ? acceleration : travel_acceleration) * steps_per_mm);
1200
 
1200
 
1201
     #if ENABLED(DISTINCT_E_FACTORS)
1201
     #if ENABLED(DISTINCT_E_FACTORS)
1202
       #define ACCEL_IDX extruder
1202
       #define ACCEL_IDX extruder
1267
         // Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds.
1267
         // Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds.
1268
         if (cos_theta > -0.95) {
1268
         if (cos_theta > -0.95) {
1269
           // Compute maximum junction velocity based on maximum acceleration and junction deviation
1269
           // Compute maximum junction velocity based on maximum acceleration and junction deviation
1270
-          float sin_theta_d2 = sqrt(0.5 * (1.0 - cos_theta)); // Trig half angle identity. Always positive.
1271
-          NOMORE(vmax_junction, sqrt(block->acceleration * junction_deviation * sin_theta_d2 / (1.0 - sin_theta_d2)));
1270
+          float sin_theta_d2 = SQRT(0.5 * (1.0 - cos_theta)); // Trig half angle identity. Always positive.
1271
+          NOMORE(vmax_junction, SQRT(block->acceleration * junction_deviation * sin_theta_d2 / (1.0 - sin_theta_d2)));
1272
         }
1272
         }
1273
       }
1273
       }
1274
     }
1274
     }
1286
   float safe_speed = block->nominal_speed;
1286
   float safe_speed = block->nominal_speed;
1287
   uint8_t limited = 0;
1287
   uint8_t limited = 0;
1288
   LOOP_XYZE(i) {
1288
   LOOP_XYZE(i) {
1289
-    const float jerk = fabs(current_speed[i]), maxj = max_jerk[i];
1289
+    const float jerk = FABS(current_speed[i]), maxj = max_jerk[i];
1290
     if (jerk > maxj) {
1290
     if (jerk > maxj) {
1291
       if (limited) {
1291
       if (limited) {
1292
         const float mjerk = maxj * block->nominal_speed;
1292
         const float mjerk = maxj * block->nominal_speed;
1395
                             && (uint32_t)esteps != block->step_event_count
1395
                             && (uint32_t)esteps != block->step_event_count
1396
                             && de_float > 0.0;
1396
                             && de_float > 0.0;
1397
     if (block->use_advance_lead)
1397
     if (block->use_advance_lead)
1398
-      block->abs_adv_steps_multiplier8 = lround(
1398
+      block->abs_adv_steps_multiplier8 = LROUND(
1399
         extruder_advance_k
1399
         extruder_advance_k
1400
         * (UNEAR_ZERO(advance_ed_ratio) ? de_float / mm_D_float : advance_ed_ratio) // Use the fixed ratio, if set
1400
         * (UNEAR_ZERO(advance_ed_ratio) ? de_float / mm_D_float : advance_ed_ratio) // Use the fixed ratio, if set
1401
         * (block->nominal_speed / (float)block->nominal_rate)
1401
         * (block->nominal_speed / (float)block->nominal_rate)
1458
   #else
1458
   #else
1459
     #define _EINDEX E_AXIS
1459
     #define _EINDEX E_AXIS
1460
   #endif
1460
   #endif
1461
-  long na = position[X_AXIS] = lround(a * axis_steps_per_mm[X_AXIS]),
1462
-       nb = position[Y_AXIS] = lround(b * axis_steps_per_mm[Y_AXIS]),
1463
-       nc = position[Z_AXIS] = lround(c * axis_steps_per_mm[Z_AXIS]),
1464
-       ne = position[E_AXIS] = lround(e * axis_steps_per_mm[_EINDEX]);
1461
+  long na = position[X_AXIS] = LROUND(a * axis_steps_per_mm[X_AXIS]),
1462
+       nb = position[Y_AXIS] = LROUND(b * axis_steps_per_mm[Y_AXIS]),
1463
+       nc = position[Z_AXIS] = LROUND(c * axis_steps_per_mm[Z_AXIS]),
1464
+       ne = position[E_AXIS] = LROUND(e * axis_steps_per_mm[_EINDEX]);
1465
   #if ENABLED(LIN_ADVANCE)
1465
   #if ENABLED(LIN_ADVANCE)
1466
     position_float[X_AXIS] = a;
1466
     position_float[X_AXIS] = a;
1467
     position_float[Y_AXIS] = b;
1467
     position_float[Y_AXIS] = b;
1514
   #else
1514
   #else
1515
     const uint8_t axis_index = axis;
1515
     const uint8_t axis_index = axis;
1516
   #endif
1516
   #endif
1517
-  position[axis] = lround(v * axis_steps_per_mm[axis_index]);
1517
+  position[axis] = LROUND(v * axis_steps_per_mm[axis_index]);
1518
   #if ENABLED(LIN_ADVANCE)
1518
   #if ENABLED(LIN_ADVANCE)
1519
     position_float[axis] = v;
1519
     position_float[axis] = v;
1520
   #endif
1520
   #endif

+ 1
- 1
Marlin/planner.h Целия файл

454
      * 'distance'.
454
      * 'distance'.
455
      */
455
      */
456
     static float max_allowable_speed(const float &accel, const float &target_velocity, const float &distance) {
456
     static float max_allowable_speed(const float &accel, const float &target_velocity, const float &distance) {
457
-      return sqrt(sq(target_velocity) - 2 * accel * distance);
457
+      return SQRT(sq(target_velocity) - 2 * accel * distance);
458
     }
458
     }
459
 
459
 
460
     static void calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor);
460
     static void calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor);

+ 1
- 1
Marlin/planner_bezier.cpp Целия файл

64
  * We approximate Euclidean distance with the sum of the coordinates
64
  * We approximate Euclidean distance with the sum of the coordinates
65
  * offset (so-called "norm 1"), which is quicker to compute.
65
  * offset (so-called "norm 1"), which is quicker to compute.
66
  */
66
  */
67
-inline static float dist1(float x1, float y1, float x2, float y2) { return fabs(x1 - x2) + fabs(y1 - y2); }
67
+inline static float dist1(float x1, float y1, float x2, float y2) { return FABS(x1 - x2) + FABS(y1 - y2); }
68
 
68
 
69
 /**
69
 /**
70
  * The algorithm for computing the step is loosely based on the one in Kig
70
  * The algorithm for computing the step is loosely based on the one in Kig

+ 4
- 4
Marlin/qr_solve.cpp Целия файл

521
       }
521
       }
522
       ix += incx;
522
       ix += incx;
523
     }
523
     }
524
-    norm = scale * sqrt(ssq);
524
+    norm = scale * SQRT(ssq);
525
   }
525
   }
526
   return norm;
526
   return norm;
527
 }
527
 }
791
           daxpy(n - l + 1, t, a + l - 1 + (l - 1)*lda, 1, a + l - 1 + (j - 1)*lda, 1);
791
           daxpy(n - l + 1, t, a + l - 1 + (l - 1)*lda, 1, a + l - 1 + (j - 1)*lda, 1);
792
           if (pl <= j && j <= pu) {
792
           if (pl <= j && j <= pu) {
793
             if (qraux[j - 1] != 0.0) {
793
             if (qraux[j - 1] != 0.0) {
794
-              tt = 1.0 - pow(r8_abs(a[l - 1 + (j - 1) * lda]) / qraux[j - 1], 2);
794
+              tt = 1.0 - POW(r8_abs(a[l - 1 + (j - 1) * lda]) / qraux[j - 1], 2);
795
               tt = r8_max(tt, 0.0);
795
               tt = r8_max(tt, 0.0);
796
               t = tt;
796
               t = tt;
797
-              tt = 1.0 + 0.05 * tt * pow(qraux[j - 1] / work[j - 1], 2);
797
+              tt = 1.0 + 0.05 * tt * POW(qraux[j - 1] / work[j - 1], 2);
798
               if (tt != 1.0)
798
               if (tt != 1.0)
799
-                qraux[j - 1] = qraux[j - 1] * sqrt(t);
799
+                qraux[j - 1] = qraux[j - 1] * SQRT(t);
800
               else {
800
               else {
801
                 qraux[j - 1] = dnrm2(n - l, a + l + (j - 1) * lda, 1);
801
                 qraux[j - 1] = dnrm2(n - l, a + l + (j - 1) * lda, 1);
802
                 work[j - 1] = qraux[j - 1];
802
                 work[j - 1] = qraux[j - 1];

+ 1
- 1
Marlin/serial.h Целия файл

40
 extern const char echomagic[] PROGMEM;
40
 extern const char echomagic[] PROGMEM;
41
 extern const char errormagic[] PROGMEM;
41
 extern const char errormagic[] PROGMEM;
42
 
42
 
43
-#define SERIAL_CHAR(x) (MYSERIAL.write(x))
43
+#define SERIAL_CHAR(x) ((void)MYSERIAL.write(x))
44
 #define SERIAL_EOL() SERIAL_CHAR('\n')
44
 #define SERIAL_EOL() SERIAL_CHAR('\n')
45
 
45
 
46
 #define SERIAL_PROTOCOLCHAR(x)              SERIAL_CHAR(x)
46
 #define SERIAL_PROTOCOLCHAR(x)              SERIAL_CHAR(x)

+ 1
- 1
Marlin/temperature.cpp Целия файл

749
 
749
 
750
     #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
750
     #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
751
       // Make sure measured temperatures are close together
751
       // Make sure measured temperatures are close together
752
-      if (fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF)
752
+      if (FABS(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF)
753
         _temp_error(0, PSTR(MSG_REDUNDANCY), PSTR(MSG_ERR_REDUNDANT_TEMP));
753
         _temp_error(0, PSTR(MSG_REDUNDANCY), PSTR(MSG_ERR_REDUNDANT_TEMP));
754
     #endif
754
     #endif
755
 
755
 

+ 4
- 4
Marlin/ubl_G29.cpp Целия файл

498
 
498
 
499
             if (parser.seen('B')) {
499
             if (parser.seen('B')) {
500
               g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(height);
500
               g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(height);
501
-              if (fabs(g29_card_thickness) > 1.5) {
501
+              if (FABS(g29_card_thickness) > 1.5) {
502
                 SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement.");
502
                 SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement.");
503
                 return;
503
                 return;
504
               }
504
               }
562
                   // P3.13 1000X distance weighting, approaches simple average of nearest points
562
                   // P3.13 1000X distance weighting, approaches simple average of nearest points
563
 
563
 
564
                   const float weight_power  = (cvf - 3.10) * 100.0,  // 3.12345 -> 2.345
564
                   const float weight_power  = (cvf - 3.10) * 100.0,  // 3.12345 -> 2.345
565
-                              weight_factor = weight_power ? pow(10.0, weight_power) : 0;
565
+                              weight_factor = weight_power ? POW(10.0, weight_power) : 0;
566
                   smart_fill_wlsf(weight_factor);
566
                   smart_fill_wlsf(weight_factor);
567
                 }
567
                 }
568
                 break;
568
                 break;
774
     SERIAL_ECHO_F(mean, 6);
774
     SERIAL_ECHO_F(mean, 6);
775
     SERIAL_EOL();
775
     SERIAL_EOL();
776
 
776
 
777
-    const float sigma = sqrt(sum_of_diff_squared / (n + 1));
777
+    const float sigma = SQRT(sum_of_diff_squared / (n + 1));
778
     SERIAL_ECHOPGM("Standard Deviation: ");
778
     SERIAL_ECHOPGM("Standard Deviation: ");
779
     SERIAL_ECHO_F(sigma, 6);
779
     SERIAL_ECHO_F(sigma, 6);
780
     SERIAL_EOL();
780
     SERIAL_EOL();
1508
         do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);    // Move the nozzle to where we are going to edit
1508
         do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);    // Move the nozzle to where we are going to edit
1509
         do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy));
1509
         do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy));
1510
 
1510
 
1511
-        new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place
1511
+        new_z = FLOOR(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place
1512
 
1512
 
1513
         KEEPALIVE_STATE(PAUSED_FOR_USER);
1513
         KEEPALIVE_STATE(PAUSED_FOR_USER);
1514
         has_control_of_lcd_panel = true;
1514
         has_control_of_lcd_panel = true;

+ 5
- 5
Marlin/ubl_motion.cpp Целия файл

492
 
492
 
493
       #if ENABLED(DELTA)  // apply delta inverse_kinematics
493
       #if ENABLED(DELTA)  // apply delta inverse_kinematics
494
 
494
 
495
-        const float delta_A = rz + sqrt( delta_diagonal_rod_2_tower[A_AXIS]
495
+        const float delta_A = rz + SQRT( delta_diagonal_rod_2_tower[A_AXIS]
496
                                          - HYPOT2( delta_tower[A_AXIS][X_AXIS] - rx,
496
                                          - HYPOT2( delta_tower[A_AXIS][X_AXIS] - rx,
497
                                                    delta_tower[A_AXIS][Y_AXIS] - ry ));
497
                                                    delta_tower[A_AXIS][Y_AXIS] - ry ));
498
 
498
 
499
-        const float delta_B = rz + sqrt( delta_diagonal_rod_2_tower[B_AXIS]
499
+        const float delta_B = rz + SQRT( delta_diagonal_rod_2_tower[B_AXIS]
500
                                          - HYPOT2( delta_tower[B_AXIS][X_AXIS] - rx,
500
                                          - HYPOT2( delta_tower[B_AXIS][X_AXIS] - rx,
501
                                                    delta_tower[B_AXIS][Y_AXIS] - ry ));
501
                                                    delta_tower[B_AXIS][Y_AXIS] - ry ));
502
 
502
 
503
-        const float delta_C = rz + sqrt( delta_diagonal_rod_2_tower[C_AXIS]
503
+        const float delta_C = rz + SQRT( delta_diagonal_rod_2_tower[C_AXIS]
504
                                          - HYPOT2( delta_tower[C_AXIS][X_AXIS] - rx,
504
                                          - HYPOT2( delta_tower[C_AXIS][X_AXIS] - rx,
505
                                                    delta_tower[C_AXIS][Y_AXIS] - ry ));
505
                                                    delta_tower[C_AXIS][Y_AXIS] - ry ));
506
 
506
 
516
         inverse_kinematics(lseg); // this writes delta[ABC] from lseg[XYZ]
516
         inverse_kinematics(lseg); // this writes delta[ABC] from lseg[XYZ]
517
                                   // should move the feedrate scaling to scara inverse_kinematics
517
                                   // should move the feedrate scaling to scara inverse_kinematics
518
 
518
 
519
-        float adiff = abs(delta[A_AXIS] - scara_oldA),
520
-              bdiff = abs(delta[B_AXIS] - scara_oldB);
519
+        const float adiff = FABS(delta[A_AXIS] - scara_oldA),
520
+                    bdiff = FABS(delta[B_AXIS] - scara_oldB);
521
         scara_oldA = delta[A_AXIS];
521
         scara_oldA = delta[A_AXIS];
522
         scara_oldB = delta[B_AXIS];
522
         scara_oldB = delta[B_AXIS];
523
         float s_feedrate = max(adiff, bdiff) * scara_feed_factor;
523
         float s_feedrate = max(adiff, bdiff) * scara_feed_factor;

+ 29
- 29
Marlin/ultralcd.cpp Целия файл

49
   bool ubl_lcd_map_control = false;
49
   bool ubl_lcd_map_control = false;
50
 #endif
50
 #endif
51
 
51
 
52
-int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2];
52
+int16_t lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2];
53
 
53
 
54
 #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
54
 #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT)
55
   millis_t previous_lcd_status_ms = 0;
55
   millis_t previous_lcd_status_ms = 0;
184
     void menu_action_setting_edit_callback_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback, const bool live=false); \
184
     void menu_action_setting_edit_callback_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback, const bool live=false); \
185
     typedef void _name##_void
185
     typedef void _name##_void
186
 
186
 
187
-  DECLARE_MENU_EDIT_TYPE(int, int3);
187
+  DECLARE_MENU_EDIT_TYPE(int16_t, int3);
188
   DECLARE_MENU_EDIT_TYPE(uint8_t, int8);
188
   DECLARE_MENU_EDIT_TYPE(uint8_t, int8);
189
   DECLARE_MENU_EDIT_TYPE(float, float3);
189
   DECLARE_MENU_EDIT_TYPE(float, float3);
190
   DECLARE_MENU_EDIT_TYPE(float, float32);
190
   DECLARE_MENU_EDIT_TYPE(float, float32);
193
   DECLARE_MENU_EDIT_TYPE(float, float51);
193
   DECLARE_MENU_EDIT_TYPE(float, float51);
194
   DECLARE_MENU_EDIT_TYPE(float, float52);
194
   DECLARE_MENU_EDIT_TYPE(float, float52);
195
   DECLARE_MENU_EDIT_TYPE(float, float62);
195
   DECLARE_MENU_EDIT_TYPE(float, float62);
196
-  DECLARE_MENU_EDIT_TYPE(unsigned long, long5);
196
+  DECLARE_MENU_EDIT_TYPE(uint32_t, long5);
197
 
197
 
198
   void menu_action_setting_edit_bool(const char* pstr, bool* ptr);
198
   void menu_action_setting_edit_bool(const char* pstr, bool* ptr);
199
   void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callbackFunc);
199
   void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callbackFunc);
602
     }
602
     }
603
 
603
 
604
     #if ENABLED(ULTIPANEL_FEEDMULTIPLY)
604
     #if ENABLED(ULTIPANEL_FEEDMULTIPLY)
605
-      const int new_frm = feedrate_percentage + (int32_t)encoderPosition;
605
+      const int16_t new_frm = feedrate_percentage + (int32_t)encoderPosition;
606
       // Dead zone at 100% feedrate
606
       // Dead zone at 100% feedrate
607
       if ((feedrate_percentage < 100 && new_frm > 100) || (feedrate_percentage > 100 && new_frm < 100)) {
607
       if ((feedrate_percentage < 100 && new_frm > 100) || (feedrate_percentage > 100 && new_frm < 100)) {
608
         feedrate_percentage = 100;
608
         feedrate_percentage = 100;
966
       if (lcd_clicked) { defer_return_to_status = false; return lcd_goto_previous_menu(); }
966
       if (lcd_clicked) { defer_return_to_status = false; return lcd_goto_previous_menu(); }
967
       ENCODER_DIRECTION_NORMAL();
967
       ENCODER_DIRECTION_NORMAL();
968
       if (encoderPosition) {
968
       if (encoderPosition) {
969
-        const int babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR);
969
+        const int16_t babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR);
970
         encoderPosition = 0;
970
         encoderPosition = 0;
971
         lcdDrawUpdate = LCDVIEW_REDRAW_NOW;
971
         lcdDrawUpdate = LCDVIEW_REDRAW_NOW;
972
         thermalManager.babystep_axis(axis, babystep_increment);
972
         thermalManager.babystep_axis(axis, babystep_increment);
990
         defer_return_to_status = true;
990
         defer_return_to_status = true;
991
         ENCODER_DIRECTION_NORMAL();
991
         ENCODER_DIRECTION_NORMAL();
992
         if (encoderPosition) {
992
         if (encoderPosition) {
993
-          const int babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR);
993
+          const int16_t babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR);
994
           encoderPosition = 0;
994
           encoderPosition = 0;
995
 
995
 
996
           const float new_zoffset = zprobe_zoffset + planner.steps_to_mm[Z_AXIS] * babystep_increment;
996
           const float new_zoffset = zprobe_zoffset + planner.steps_to_mm[Z_AXIS] * babystep_increment;
1021
 
1021
 
1022
     float mesh_edit_value, mesh_edit_accumulator; // We round mesh_edit_value to 2.5 decimal places. So we keep a
1022
     float mesh_edit_value, mesh_edit_accumulator; // We round mesh_edit_value to 2.5 decimal places. So we keep a
1023
                                                   // separate value that doesn't lose precision.
1023
                                                   // separate value that doesn't lose precision.
1024
-    static int ubl_encoderPosition = 0;
1024
+    static int16_t ubl_encoderPosition = 0;
1025
 
1025
 
1026
     static void _lcd_mesh_fine_tune(const char* msg) {
1026
     static void _lcd_mesh_fine_tune(const char* msg) {
1027
       defer_return_to_status = true;
1027
       defer_return_to_status = true;
1275
    * "Prepare" submenu items
1275
    * "Prepare" submenu items
1276
    *
1276
    *
1277
    */
1277
    */
1278
-  void _lcd_preheat(const int endnum, const int16_t temph, const int16_t tempb, const int16_t fan) {
1278
+  void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const int16_t fan) {
1279
     if (temph > 0) thermalManager.setTargetHotend(min(heater_maxtemp[endnum], temph), endnum);
1279
     if (temph > 0) thermalManager.setTargetHotend(min(heater_maxtemp[endnum], temph), endnum);
1280
     #if TEMP_SENSOR_BED != 0
1280
     #if TEMP_SENSOR_BED != 0
1281
       if (tempb >= 0) thermalManager.setTargetBed(tempb);
1281
       if (tempb >= 0) thermalManager.setTargetBed(tempb);
1806
 
1806
 
1807
     void _lcd_ubl_level_bed();
1807
     void _lcd_ubl_level_bed();
1808
 
1808
 
1809
-    static int ubl_storage_slot = 0,
1809
+    static int16_t ubl_storage_slot = 0,
1810
                custom_bed_temp = 50,
1810
                custom_bed_temp = 50,
1811
                custom_hotend_temp = 190,
1811
                custom_hotend_temp = 190,
1812
                side_points = 3,
1812
                side_points = 3,
2624
       // This assumes the center is 0,0
2624
       // This assumes the center is 0,0
2625
       #if ENABLED(DELTA)
2625
       #if ENABLED(DELTA)
2626
         if (axis != Z_AXIS) {
2626
         if (axis != Z_AXIS) {
2627
-          max = sqrt(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis]));
2627
+          max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis]));
2628
           min = -max;
2628
           min = -max;
2629
         }
2629
         }
2630
       #endif
2630
       #endif
2872
   #if ENABLED(PID_AUTOTUNE_MENU)
2872
   #if ENABLED(PID_AUTOTUNE_MENU)
2873
 
2873
 
2874
     #if ENABLED(PIDTEMP)
2874
     #if ENABLED(PIDTEMP)
2875
-      int autotune_temp[HOTENDS] = ARRAY_BY_HOTENDS1(150);
2875
+      int16_t autotune_temp[HOTENDS] = ARRAY_BY_HOTENDS1(150);
2876
     #endif
2876
     #endif
2877
 
2877
 
2878
     #if ENABLED(PIDTEMPBED)
2878
     #if ENABLED(PIDTEMPBED)
2879
-      int autotune_temp_bed = 70;
2879
+      int16_t autotune_temp_bed = 70;
2880
     #endif
2880
     #endif
2881
 
2881
 
2882
-    void _lcd_autotune(int e) {
2882
+    void _lcd_autotune(int16_t e) {
2883
       char cmd[30];
2883
       char cmd[30];
2884
       sprintf_P(cmd, PSTR("M303 U1 E%i S%i"), e,
2884
       sprintf_P(cmd, PSTR("M303 U1 E%i S%i"), e,
2885
         #if HAS_PID_FOR_BOTH
2885
         #if HAS_PID_FOR_BOTH
2899
 
2899
 
2900
     // Helpers for editing PID Ki & Kd values
2900
     // Helpers for editing PID Ki & Kd values
2901
     // grab the PID value out of the temp variable; scale it; then update the PID driver
2901
     // grab the PID value out of the temp variable; scale it; then update the PID driver
2902
-    void copy_and_scalePID_i(int e) {
2902
+    void copy_and_scalePID_i(int16_t e) {
2903
       #if DISABLED(PID_PARAMS_PER_HOTEND) || HOTENDS == 1
2903
       #if DISABLED(PID_PARAMS_PER_HOTEND) || HOTENDS == 1
2904
         UNUSED(e);
2904
         UNUSED(e);
2905
       #endif
2905
       #endif
2906
       PID_PARAM(Ki, e) = scalePID_i(raw_Ki);
2906
       PID_PARAM(Ki, e) = scalePID_i(raw_Ki);
2907
       thermalManager.updatePID();
2907
       thermalManager.updatePID();
2908
     }
2908
     }
2909
-    void copy_and_scalePID_d(int e) {
2909
+    void copy_and_scalePID_d(int16_t e) {
2910
       #if DISABLED(PID_PARAMS_PER_HOTEND) || HOTENDS == 1
2910
       #if DISABLED(PID_PARAMS_PER_HOTEND) || HOTENDS == 1
2911
         UNUSED(e);
2911
         UNUSED(e);
2912
       #endif
2912
       #endif
3475
         STATIC_ITEM(MSG_INFO_PRINT_LONGEST ": ", false, false);                                        // Longest job time:
3475
         STATIC_ITEM(MSG_INFO_PRINT_LONGEST ": ", false, false);                                        // Longest job time:
3476
         STATIC_ITEM("", false, false, buffer);                                                         // 99y 364d 23h 59m 59s
3476
         STATIC_ITEM("", false, false, buffer);                                                         // 99y 364d 23h 59m 59s
3477
 
3477
 
3478
-        sprintf_P(buffer, PSTR("%ld.%im"), long(stats.filamentUsed / 1000), int(stats.filamentUsed / 100) % 10);
3478
+        sprintf_P(buffer, PSTR("%ld.%im"), long(stats.filamentUsed / 1000), int16_t(stats.filamentUsed / 100) % 10);
3479
         STATIC_ITEM(MSG_INFO_PRINT_FILAMENT ": ", false, false);                                       // Extruded total:
3479
         STATIC_ITEM(MSG_INFO_PRINT_FILAMENT ": ", false, false);                                       // Extruded total:
3480
         STATIC_ITEM("", false, false, buffer);                                                         // 125m
3480
         STATIC_ITEM("", false, false, buffer);                                                         // 125m
3481
         END_SCREEN();
3481
         END_SCREEN();
3878
    *
3878
    *
3879
    * The "DEFINE_MENU_EDIT_TYPE" macro generates the functions needed to edit a numerical value.
3879
    * The "DEFINE_MENU_EDIT_TYPE" macro generates the functions needed to edit a numerical value.
3880
    *
3880
    *
3881
-   * For example, DEFINE_MENU_EDIT_TYPE(int, int3, itostr3, 1) expands into these functions:
3881
+   * For example, DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1) expands into these functions:
3882
    *
3882
    *
3883
    *   bool _menu_edit_int3();
3883
    *   bool _menu_edit_int3();
3884
-   *   void menu_edit_int3(); // edit int (interactively)
3885
-   *   void menu_edit_callback_int3(); // edit int (interactively) with callback on completion
3886
-   *   void _menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue);
3887
-   *   void menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue);
3888
-   *   void menu_action_setting_edit_callback_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue, const screenFunc_t callback, const bool live); // edit int with callback
3884
+   *   void menu_edit_int3(); // edit int16_t (interactively)
3885
+   *   void menu_edit_callback_int3(); // edit int16_t (interactively) with callback on completion
3886
+   *   void _menu_action_setting_edit_int3(const char * const pstr, int16_t * const ptr, const int16_t minValue, const int16_t maxValue);
3887
+   *   void menu_action_setting_edit_int3(const char * const pstr, int16_t * const ptr, const int16_t minValue, const int16_t maxValue);
3888
+   *   void menu_action_setting_edit_callback_int3(const char * const pstr, int16_t * const ptr, const int16_t minValue, const int16_t maxValue, const screenFunc_t callback, const bool live); // edit int16_t with callback
3889
    *
3889
    *
3890
    * You can then use one of the menu macros to present the edit interface:
3890
    * You can then use one of the menu macros to present the edit interface:
3891
    *   MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_percentage, 10, 999)
3891
    *   MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_percentage, 10, 999)
3936
     } \
3936
     } \
3937
     typedef void _name
3937
     typedef void _name
3938
 
3938
 
3939
-  DEFINE_MENU_EDIT_TYPE(int, int3, itostr3, 1);
3939
+  DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1);
3940
   DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1);
3940
   DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1);
3941
   DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1.0);
3941
   DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1.0);
3942
   DEFINE_MENU_EDIT_TYPE(float, float32, ftostr32, 100.0);
3942
   DEFINE_MENU_EDIT_TYPE(float, float32, ftostr32, 100.0);
3945
   DEFINE_MENU_EDIT_TYPE(float, float51, ftostr51sign, 10.0);
3945
   DEFINE_MENU_EDIT_TYPE(float, float51, ftostr51sign, 10.0);
3946
   DEFINE_MENU_EDIT_TYPE(float, float52, ftostr52sign, 100.0);
3946
   DEFINE_MENU_EDIT_TYPE(float, float52, ftostr52sign, 100.0);
3947
   DEFINE_MENU_EDIT_TYPE(float, float62, ftostr62rj, 100.0);
3947
   DEFINE_MENU_EDIT_TYPE(float, float62, ftostr62rj, 100.0);
3948
-  DEFINE_MENU_EDIT_TYPE(unsigned long, long5, ftostr5rj, 0.01);
3948
+  DEFINE_MENU_EDIT_TYPE(uint32_t, long5, ftostr5rj, 0.01);
3949
 
3949
 
3950
   /**
3950
   /**
3951
    *
3951
    *
3953
    *
3953
    *
3954
    */
3954
    */
3955
   #if ENABLED(REPRAPWORLD_KEYPAD)
3955
   #if ENABLED(REPRAPWORLD_KEYPAD)
3956
-    void _reprapworld_keypad_move(AxisEnum axis, int dir) {
3956
+    void _reprapworld_keypad_move(AxisEnum axis, int16_t dir) {
3957
       move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
3957
       move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
3958
       encoderPosition = dir;
3958
       encoderPosition = dir;
3959
       switch (axis) {
3959
       switch (axis) {
4112
   #endif
4112
   #endif
4113
 }
4113
 }
4114
 
4114
 
4115
-int lcd_strlen(const char* s) {
4116
-  int i = 0, j = 0;
4115
+int16_t lcd_strlen(const char* s) {
4116
+  int16_t i = 0, j = 0;
4117
   while (s[i]) {
4117
   while (s[i]) {
4118
     if (PRINTABLE(s[i])) j++;
4118
     if (PRINTABLE(s[i])) j++;
4119
     i++;
4119
     i++;
4121
   return j;
4121
   return j;
4122
 }
4122
 }
4123
 
4123
 
4124
-int lcd_strlen_P(const char* s) {
4125
-  int j = 0;
4124
+int16_t lcd_strlen_P(const char* s) {
4125
+  int16_t j = 0;
4126
   while (pgm_read_byte(s)) {
4126
   while (pgm_read_byte(s)) {
4127
     if (PRINTABLE(pgm_read_byte(s))) j++;
4127
     if (PRINTABLE(pgm_read_byte(s))) j++;
4128
     s++;
4128
     s++;

+ 3
- 3
Marlin/ultralcd.h Целия файл

30
   #define BUTTON_EXISTS(BN) (defined(BTN_## BN) && BTN_## BN >= 0)
30
   #define BUTTON_EXISTS(BN) (defined(BTN_## BN) && BTN_## BN >= 0)
31
   #define BUTTON_PRESSED(BN) !READ(BTN_## BN)
31
   #define BUTTON_PRESSED(BN) !READ(BTN_## BN)
32
 
32
 
33
-  extern int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2];
33
+  extern int16_t lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2];
34
 
34
 
35
-  int lcd_strlen(const char* s);
36
-  int lcd_strlen_P(const char* s);
35
+  int16_t lcd_strlen(const char* s);
36
+  int16_t lcd_strlen_P(const char* s);
37
   void lcd_update();
37
   void lcd_update();
38
   void lcd_init();
38
   void lcd_init();
39
   bool lcd_hasstatus();
39
   bool lcd_hasstatus();

+ 5
- 5
Marlin/ultralcd_impl_DOGM.h Целия файл

346
 // Status Screen
346
 // Status Screen
347
 //
347
 //
348
 
348
 
349
-FORCE_INLINE void _draw_centered_temp(const int temp, const uint8_t x, const uint8_t y) {
349
+FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t x, const uint8_t y) {
350
   const uint8_t degsize = 6 * (temp >= 100 ? 3 : temp >= 10 ? 2 : 1); // number's pixel width
350
   const uint8_t degsize = 6 * (temp >= 100 ? 3 : temp >= 10 ? 2 : 1); // number's pixel width
351
   u8g.setPrintPos(x - (18 - degsize) / 2, y); // move left if shorter
351
   u8g.setPrintPos(x - (18 - degsize) / 2, y); // move left if shorter
352
   lcd_print(itostr3(temp));
352
   lcd_print(itostr3(temp));
484
     #if HAS_FAN0
484
     #if HAS_FAN0
485
       if (PAGE_CONTAINS(20, 27)) {
485
       if (PAGE_CONTAINS(20, 27)) {
486
         // Fan
486
         // Fan
487
-        const int per = ((fanSpeeds[0] + 1) * 100) / 256;
487
+        const int16_t per = ((fanSpeeds[0] + 1) * 100) / 256;
488
         if (per) {
488
         if (per) {
489
           u8g.setPrintPos(104, 27);
489
           u8g.setPrintPos(104, 27);
490
           lcd_print(itostr3(per));
490
           lcd_print(itostr3(per));
533
       if (PAGE_CONTAINS(50, 51 - (TALL_FONT_CORRECTION)))     // 50-51 (or just 50)
533
       if (PAGE_CONTAINS(50, 51 - (TALL_FONT_CORRECTION)))     // 50-51 (or just 50)
534
         u8g.drawBox(
534
         u8g.drawBox(
535
           PROGRESS_BAR_X + 1, 50,
535
           PROGRESS_BAR_X + 1, 50,
536
-          (unsigned int)((PROGRESS_BAR_WIDTH - 2) * card.percentDone() * 0.01), 2 - (TALL_FONT_CORRECTION)
536
+          (uint16_t)((PROGRESS_BAR_WIDTH - 2) * card.percentDone() * 0.01), 2 - (TALL_FONT_CORRECTION)
537
         );
537
         );
538
 
538
 
539
       //
539
       //
847
     } \
847
     } \
848
     typedef void _name##_void
848
     typedef void _name##_void
849
 
849
 
850
-  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int, int3, itostr3);
850
+  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int16_t, int3, itostr3);
851
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3);
851
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3);
852
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3);
852
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3);
853
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32);
853
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32);
856
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign);
856
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign);
857
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign);
857
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign);
858
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj);
858
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj);
859
-  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(unsigned long, long5, ftostr5rj);
859
+  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint32_t, long5, ftostr5rj);
860
 
860
 
861
   #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
861
   #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
862
   #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
862
   #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))

+ 9
- 9
Marlin/ultralcd_impl_HD44780.h Целия файл

337
       if (info_screen_charset != char_mode) {
337
       if (info_screen_charset != char_mode) {
338
         char_mode = info_screen_charset;
338
         char_mode = info_screen_charset;
339
         if (info_screen_charset) { // Progress bar characters for info screen
339
         if (info_screen_charset) { // Progress bar characters for info screen
340
-          for (int i = 3; i--;) createChar_P(LCD_STR_PROGRESS[i], progress[i]);
340
+          for (int16_t i = 3; i--;) createChar_P(LCD_STR_PROGRESS[i], progress[i]);
341
         }
341
         }
342
         else { // Custom characters for submenus
342
         else { // Custom characters for submenus
343
           createChar_P(LCD_UPLEVEL_CHAR, uplevel);
343
           createChar_P(LCD_UPLEVEL_CHAR, uplevel);
414
 
414
 
415
 #if ENABLED(SHOW_BOOTSCREEN)
415
 #if ENABLED(SHOW_BOOTSCREEN)
416
 
416
 
417
-  void lcd_erase_line(const int line) {
417
+  void lcd_erase_line(const int16_t line) {
418
     lcd.setCursor(0, line);
418
     lcd.setCursor(0, line);
419
     for (uint8_t i = LCD_WIDTH + 1; --i;)
419
     for (uint8_t i = LCD_WIDTH + 1; --i;)
420
       lcd.print(' ');
420
       lcd.print(' ');
421
   }
421
   }
422
 
422
 
423
   // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line
423
   // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line
424
-  void lcd_scroll(const int col, const int line, const char* const text, const int len, const int time) {
424
+  void lcd_scroll(const int16_t col, const int16_t line, const char* const text, const int16_t len, const int16_t time) {
425
     char tmp[LCD_WIDTH + 1] = {0};
425
     char tmp[LCD_WIDTH + 1] = {0};
426
-    int n = max(lcd_strlen_P(text) - len, 0);
427
-    for (int i = 0; i <= n; i++) {
426
+    int16_t n = max(lcd_strlen_P(text) - len, 0);
427
+    for (int16_t i = 0; i <= n; i++) {
428
       strncpy_P(tmp, text + i, min(len, LCD_WIDTH));
428
       strncpy_P(tmp, text + i, min(len, LCD_WIDTH));
429
       lcd.setCursor(col, line);
429
       lcd.setCursor(col, line);
430
       lcd_print(tmp);
430
       lcd_print(tmp);
433
   }
433
   }
434
 
434
 
435
   static void logo_lines(const char* const extra) {
435
   static void logo_lines(const char* const extra) {
436
-    int indent = (LCD_WIDTH - 8 - lcd_strlen_P(extra)) / 2;
436
+    int16_t indent = (LCD_WIDTH - 8 - lcd_strlen_P(extra)) / 2;
437
     lcd.setCursor(indent, 0); lcd.print('\x00'); lcd_printPGM(PSTR( "------" ));  lcd.print('\x01');
437
     lcd.setCursor(indent, 0); lcd.print('\x00'); lcd_printPGM(PSTR( "------" ));  lcd.print('\x01');
438
     lcd.setCursor(indent, 1);                    lcd_printPGM(PSTR("|Marlin|"));  lcd_printPGM(extra);
438
     lcd.setCursor(indent, 1);                    lcd_printPGM(PSTR("|Marlin|"));  lcd_printPGM(extra);
439
     lcd.setCursor(indent, 2); lcd.print('\x02'); lcd_printPGM(PSTR( "------" ));  lcd.print('\x03');
439
     lcd.setCursor(indent, 2); lcd.print('\x02'); lcd_printPGM(PSTR( "------" ));  lcd.print('\x03');
628
 #if ENABLED(LCD_PROGRESS_BAR)
628
 #if ENABLED(LCD_PROGRESS_BAR)
629
 
629
 
630
   inline void lcd_draw_progress_bar(const uint8_t percent) {
630
   inline void lcd_draw_progress_bar(const uint8_t percent) {
631
-    const int tix = (int)(percent * (LCD_WIDTH) * 3) / 100,
631
+    const int16_t tix = (int16_t)(percent * (LCD_WIDTH) * 3) / 100,
632
               cel = tix / 3,
632
               cel = tix / 3,
633
               rem = tix % 3;
633
               rem = tix % 3;
634
     uint8_t i = LCD_WIDTH;
634
     uint8_t i = LCD_WIDTH;
958
     } \
958
     } \
959
     typedef void _name##_void
959
     typedef void _name##_void
960
 
960
 
961
-  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int, int3, itostr3);
961
+  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int16_t, int3, itostr3);
962
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3);
962
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3);
963
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3);
963
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3);
964
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32);
964
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32);
967
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign);
967
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign);
968
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign);
968
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign);
969
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj);
969
   DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj);
970
-  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(unsigned long, long5, ftostr5rj);
970
+  DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint32_t, long5, ftostr5rj);
971
 
971
 
972
   #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
972
   #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
973
   #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
973
   #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))

+ 1
- 1
Marlin/vector_3.cpp Целия файл

63
   return normalized;
63
   return normalized;
64
 }
64
 }
65
 
65
 
66
-float vector_3::get_length() { return sqrt(sq(x) + sq(y) + sq(z)); }
66
+float vector_3::get_length() { return SQRT(sq(x) + sq(y) + sq(z)); }
67
 
67
 
68
 void vector_3::normalize() {
68
 void vector_3::normalize() {
69
   const float inv_length = 1.0 / get_length();
69
   const float inv_length = 1.0 / get_length();

Loading…
Отказ
Запис