|
@@ -1350,7 +1350,10 @@ static void set_axis_is_at_home(AxisEnum axis) {
|
1350
|
1350
|
}
|
1351
|
1351
|
#endif
|
1352
|
1352
|
|
|
1353
|
+ axis_known_position[axis] = axis_homed[axis] = true;
|
|
1354
|
+
|
1353
|
1355
|
position_shift[axis] = 0;
|
|
1356
|
+ update_software_endstops(axis);
|
1354
|
1357
|
|
1355
|
1358
|
#if ENABLED(DUAL_X_CARRIAGE)
|
1356
|
1359
|
if (axis == X_AXIS && (active_extruder != 0 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) {
|
|
@@ -1396,7 +1399,6 @@ static void set_axis_is_at_home(AxisEnum axis) {
|
1396
|
1399
|
#endif
|
1397
|
1400
|
{
|
1398
|
1401
|
current_position[axis] = LOGICAL_POSITION(base_home_pos(axis), axis);
|
1399
|
|
- update_software_endstops(axis);
|
1400
|
1402
|
|
1401
|
1403
|
if (axis == Z_AXIS) {
|
1402
|
1404
|
#if HAS_BED_PROBE && Z_HOME_DIR < 0
|
|
@@ -1429,8 +1431,6 @@ static void set_axis_is_at_home(AxisEnum axis) {
|
1429
|
1431
|
SERIAL_ECHOLNPGM(")");
|
1430
|
1432
|
}
|
1431
|
1433
|
#endif
|
1432
|
|
-
|
1433
|
|
- axis_known_position[axis] = axis_homed[axis] = true;
|
1434
|
1434
|
}
|
1435
|
1435
|
|
1436
|
1436
|
/**
|
|
@@ -1446,38 +1446,38 @@ inline float get_homing_bump_feedrate(AxisEnum axis) {
|
1446
|
1446
|
}
|
1447
|
1447
|
return homing_feedrate_mm_s[axis] / hbd;
|
1448
|
1448
|
}
|
1449
|
|
-//
|
1450
|
|
-// line_to_current_position
|
1451
|
|
-// Move the planner to the current position from wherever it last moved
|
1452
|
|
-// (or from wherever it has been told it is located).
|
1453
|
|
-//
|
1454
|
|
-inline void line_to_current_position() {
|
1455
|
|
- planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate_mm_s, active_extruder);
|
1456
|
|
-}
|
1457
|
1449
|
|
1458
|
|
-inline void line_to_z(float zPosition) {
|
1459
|
|
- planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate_mm_s, active_extruder);
|
1460
|
|
-}
|
|
1450
|
+#if !IS_KINEMATIC
|
|
1451
|
+ //
|
|
1452
|
+ // line_to_current_position
|
|
1453
|
+ // Move the planner to the current position from wherever it last moved
|
|
1454
|
+ // (or from wherever it has been told it is located).
|
|
1455
|
+ //
|
|
1456
|
+ inline void line_to_current_position() {
|
|
1457
|
+ planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate_mm_s, active_extruder);
|
|
1458
|
+ }
|
1461
|
1459
|
|
1462
|
|
-//
|
1463
|
|
-// line_to_destination
|
1464
|
|
-// Move the planner, not necessarily synced with current_position
|
1465
|
|
-//
|
1466
|
|
-inline void line_to_destination(float fr_mm_s) {
|
1467
|
|
- planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], fr_mm_s, active_extruder);
|
1468
|
|
-}
|
1469
|
|
-inline void line_to_destination() { line_to_destination(feedrate_mm_s); }
|
|
1460
|
+ //
|
|
1461
|
+ // line_to_destination
|
|
1462
|
+ // Move the planner, not necessarily synced with current_position
|
|
1463
|
+ //
|
|
1464
|
+ inline void line_to_destination(float fr_mm_s) {
|
|
1465
|
+ planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], fr_mm_s, active_extruder);
|
|
1466
|
+ }
|
|
1467
|
+ inline void line_to_destination() { line_to_destination(feedrate_mm_s); }
|
|
1468
|
+
|
|
1469
|
+#endif // !IS_KINEMATIC
|
1470
|
1470
|
|
1471
|
1471
|
inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); }
|
1472
|
1472
|
inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); }
|
1473
|
1473
|
|
1474
|
|
-#if ENABLED(DELTA)
|
|
1474
|
+#if IS_KINEMATIC
|
1475
|
1475
|
/**
|
1476
|
1476
|
* Calculate delta, start a line, and set current_position to destination
|
1477
|
1477
|
*/
|
1478
|
|
- void prepare_move_to_destination_raw() {
|
|
1478
|
+ void prepare_uninterpolated_move_to_destination() {
|
1479
|
1479
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
1480
|
|
- if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_move_to_destination_raw", destination);
|
|
1480
|
+ if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_uninterpolated_move_to_destination", destination);
|
1481
|
1481
|
#endif
|
1482
|
1482
|
refresh_cmd_timeout();
|
1483
|
1483
|
inverse_kinematics(destination);
|
|
@@ -1513,7 +1513,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f
|
1513
|
1513
|
destination[X_AXIS] = x; // move directly (uninterpolated)
|
1514
|
1514
|
destination[Y_AXIS] = y;
|
1515
|
1515
|
destination[Z_AXIS] = z;
|
1516
|
|
- prepare_move_to_destination_raw(); // set_current_to_destination
|
|
1516
|
+ prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
1517
|
1517
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
1518
|
1518
|
if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
|
1519
|
1519
|
#endif
|
|
@@ -1521,7 +1521,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f
|
1521
|
1521
|
}
|
1522
|
1522
|
else {
|
1523
|
1523
|
destination[Z_AXIS] = delta_clip_start_height;
|
1524
|
|
- prepare_move_to_destination_raw(); // set_current_to_destination
|
|
1524
|
+ prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
1525
|
1525
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
1526
|
1526
|
if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
|
1527
|
1527
|
#endif
|
|
@@ -1530,7 +1530,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f
|
1530
|
1530
|
|
1531
|
1531
|
if (z > current_position[Z_AXIS]) { // raising?
|
1532
|
1532
|
destination[Z_AXIS] = z;
|
1533
|
|
- prepare_move_to_destination_raw(); // set_current_to_destination
|
|
1533
|
+ prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
1534
|
1534
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
1535
|
1535
|
if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
|
1536
|
1536
|
#endif
|
|
@@ -1545,7 +1545,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f
|
1545
|
1545
|
|
1546
|
1546
|
if (z < current_position[Z_AXIS]) { // lowering?
|
1547
|
1547
|
destination[Z_AXIS] = z;
|
1548
|
|
- prepare_move_to_destination_raw(); // set_current_to_destination
|
|
1548
|
+ prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
1549
|
1549
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
1550
|
1550
|
if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
|
1551
|
1551
|
#endif
|
|
@@ -1555,6 +1555,30 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f
|
1555
|
1555
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to");
|
1556
|
1556
|
#endif
|
1557
|
1557
|
|
|
1558
|
+ #elif IS_SCARA
|
|
1559
|
+
|
|
1560
|
+ set_destination_to_current();
|
|
1561
|
+
|
|
1562
|
+ // If Z needs to raise, do it before moving XY
|
|
1563
|
+ if (current_position[Z_AXIS] < z) {
|
|
1564
|
+ feedrate_mm_s = (fr_mm_s != 0.0) ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS];
|
|
1565
|
+ destination[Z_AXIS] = z;
|
|
1566
|
+ prepare_uninterpolated_move_to_destination();
|
|
1567
|
+ }
|
|
1568
|
+
|
|
1569
|
+ feedrate_mm_s = (fr_mm_s != 0.0) ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
|
|
1570
|
+
|
|
1571
|
+ destination[X_AXIS] = x;
|
|
1572
|
+ destination[Y_AXIS] = y;
|
|
1573
|
+ prepare_uninterpolated_move_to_destination();
|
|
1574
|
+
|
|
1575
|
+ // If Z needs to lower, do it after moving XY
|
|
1576
|
+ if (current_position[Z_AXIS] > z) {
|
|
1577
|
+ feedrate_mm_s = (fr_mm_s != 0.0) ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS];
|
|
1578
|
+ destination[Z_AXIS] = z;
|
|
1579
|
+ prepare_uninterpolated_move_to_destination();
|
|
1580
|
+ }
|
|
1581
|
+
|
1558
|
1582
|
#else
|
1559
|
1583
|
|
1560
|
1584
|
// If Z needs to raise, do it before moving XY
|
|
@@ -2230,10 +2254,15 @@ static void do_homing_move(AxisEnum axis, float where, float fr_mm_s = 0.0) {
|
2230
|
2254
|
#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
|
2231
|
2255
|
|
2232
|
2256
|
static void homeaxis(AxisEnum axis) {
|
2233
|
|
- #define CAN_HOME(A) \
|
2234
|
|
- (axis == A##_AXIS && ((A##_MIN_PIN > -1 && A##_HOME_DIR < 0) || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0)))
|
2235
|
2257
|
|
2236
|
|
- if (!CAN_HOME(X) && !CAN_HOME(Y) && !CAN_HOME(Z)) return;
|
|
2258
|
+ #if IS_SCARA
|
|
2259
|
+ // Only Z homing (with probe) is permitted
|
|
2260
|
+ if (axis != Z_AXIS) { BUZZ(100, 880); return; }
|
|
2261
|
+ #else
|
|
2262
|
+ #define CAN_HOME(A) \
|
|
2263
|
+ (axis == A##_AXIS && ((A##_MIN_PIN > -1 && A##_HOME_DIR < 0) || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0)))
|
|
2264
|
+ if (!CAN_HOME(X) && !CAN_HOME(Y) && !CAN_HOME(Z)) return;
|
|
2265
|
+ #endif
|
2237
|
2266
|
|
2238
|
2267
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
2239
|
2268
|
if (DEBUGGING(LEVELING)) {
|
|
@@ -2296,10 +2325,16 @@ static void homeaxis(AxisEnum axis) {
|
2296
|
2325
|
} // Z_AXIS
|
2297
|
2326
|
#endif
|
2298
|
2327
|
|
2299
|
|
- // Delta has already moved all three towers up in G28
|
2300
|
|
- // so here it re-homes each tower in turn.
|
2301
|
|
- // Delta homing treats the axes as normal linear axes.
|
2302
|
|
- #if ENABLED(DELTA)
|
|
2328
|
+ #if IS_SCARA
|
|
2329
|
+
|
|
2330
|
+ set_axis_is_at_home(axis);
|
|
2331
|
+ SYNC_PLAN_POSITION_KINEMATIC();
|
|
2332
|
+
|
|
2333
|
+ #elif ENABLED(DELTA)
|
|
2334
|
+
|
|
2335
|
+ // Delta has already moved all three towers up in G28
|
|
2336
|
+ // so here it re-homes each tower in turn.
|
|
2337
|
+ // Delta homing treats the axes as normal linear axes.
|
2303
|
2338
|
|
2304
|
2339
|
// retrace by the amount specified in endstop_adj
|
2305
|
2340
|
if (endstop_adj[axis] * Z_HOME_DIR < 0) {
|
|
@@ -2492,16 +2527,26 @@ void unknown_command_error() {
|
2492
|
2527
|
|
2493
|
2528
|
bool position_is_reachable(float target[XYZ]) {
|
2494
|
2529
|
float dx = RAW_X_POSITION(target[X_AXIS]),
|
2495
|
|
- dy = RAW_Y_POSITION(target[Y_AXIS]);
|
|
2530
|
+ dy = RAW_Y_POSITION(target[Y_AXIS]),
|
|
2531
|
+ dz = RAW_Z_POSITION(target[Z_AXIS]);
|
2496
|
2532
|
|
2497
|
|
- #if ENABLED(DELTA)
|
2498
|
|
- return HYPOT2(dx, dy) <= sq(DELTA_PRINTABLE_RADIUS);
|
|
2533
|
+ bool good;
|
|
2534
|
+ #if IS_SCARA
|
|
2535
|
+ #if MIDDLE_DEAD_ZONE_R > 0
|
|
2536
|
+ const float R2 = HYPOT2(dx - SCARA_OFFSET_X, dy - SCARA_OFFSET_Y);
|
|
2537
|
+ good = (R2 >= sq(float(MIDDLE_DEAD_ZONE_R))) && (R2 <= sq(L1 + L2));
|
|
2538
|
+ #else
|
|
2539
|
+ good = HYPOT2(dx - SCARA_OFFSET_X, dy - SCARA_OFFSET_Y) <= sq(L1 + L2);
|
|
2540
|
+ #endif
|
|
2541
|
+ #elif ENABLED(DELTA)
|
|
2542
|
+ good = HYPOT2(dx, dy) <= sq(DELTA_PRINTABLE_RADIUS);
|
2499
|
2543
|
#else
|
2500
|
|
- float dz = RAW_Z_POSITION(target[Z_AXIS]);
|
2501
|
|
- return dx >= X_MIN_POS - 0.0001 && dx <= X_MAX_POS + 0.0001
|
2502
|
|
- && dy >= Y_MIN_POS - 0.0001 && dy <= Y_MAX_POS + 0.0001
|
2503
|
|
- && dz >= Z_MIN_POS - 0.0001 && dz <= Z_MAX_POS + 0.0001;
|
|
2544
|
+ good = true;
|
2504
|
2545
|
#endif
|
|
2546
|
+
|
|
2547
|
+ return good && dx >= X_MIN_POS - 0.0001 && dx <= X_MAX_POS + 0.0001
|
|
2548
|
+ && dy >= Y_MIN_POS - 0.0001 && dy <= Y_MAX_POS + 0.0001
|
|
2549
|
+ && dz >= Z_MIN_POS - 0.0001 && dz <= Z_MAX_POS + 0.0001;
|
2505
|
2550
|
}
|
2506
|
2551
|
|
2507
|
2552
|
/**************************************************
|
|
@@ -2511,7 +2556,11 @@ bool position_is_reachable(float target[XYZ]) {
|
2511
|
2556
|
/**
|
2512
|
2557
|
* G0, G1: Coordinated movement of X Y Z E axes
|
2513
|
2558
|
*/
|
2514
|
|
-inline void gcode_G0_G1() {
|
|
2559
|
+inline void gcode_G0_G1(
|
|
2560
|
+ #if IS_SCARA
|
|
2561
|
+ bool fast_move=false
|
|
2562
|
+ #endif
|
|
2563
|
+) {
|
2515
|
2564
|
if (IsRunning()) {
|
2516
|
2565
|
gcode_get_destination(); // For X Y Z E F
|
2517
|
2566
|
|
|
@@ -2530,7 +2579,11 @@ inline void gcode_G0_G1() {
|
2530
|
2579
|
|
2531
|
2580
|
#endif //FWRETRACT
|
2532
|
2581
|
|
2533
|
|
- prepare_move_to_destination();
|
|
2582
|
+ #if IS_SCARA
|
|
2583
|
+ fast_move ? prepare_uninterpolated_move_to_destination() : prepare_move_to_destination();
|
|
2584
|
+ #else
|
|
2585
|
+ prepare_move_to_destination();
|
|
2586
|
+ #endif
|
2534
|
2587
|
}
|
2535
|
2588
|
}
|
2536
|
2589
|
|
|
@@ -2779,8 +2832,7 @@ inline void gcode_G4() {
|
2779
|
2832
|
|
2780
|
2833
|
// Move all carriages together linearly until an endstop is hit.
|
2781
|
2834
|
current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (Z_MAX_LENGTH + 10);
|
2782
|
|
- feedrate_mm_s = homing_feedrate_mm_s[X_AXIS];
|
2783
|
|
- line_to_current_position();
|
|
2835
|
+ planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate_mm_s[X_AXIS], active_extruder);
|
2784
|
2836
|
stepper.synchronize();
|
2785
|
2837
|
endstops.hit_on_purpose(); // clear endstop hit flags
|
2786
|
2838
|
|
|
@@ -3440,20 +3492,8 @@ inline void gcode_G28() {
|
3440
|
3492
|
// Re-orient the current position without leveling
|
3441
|
3493
|
// based on where the steppers are positioned.
|
3442
|
3494
|
//
|
3443
|
|
- #if IS_KINEMATIC
|
3444
|
|
-
|
3445
|
|
- // For DELTA/SCARA we need to apply forward kinematics.
|
3446
|
|
- // This returns raw positions and we remap to the space.
|
3447
|
|
- get_cartesian_from_steppers();
|
3448
|
|
- LOOP_XYZ(i) current_position[i] = LOGICAL_POSITION(cartes[i], i);
|
3449
|
|
-
|
3450
|
|
- #else
|
3451
|
|
-
|
3452
|
|
- // For cartesian/core the steppers are already mapped to
|
3453
|
|
- // the coordinate space by design.
|
3454
|
|
- LOOP_XYZ(i) current_position[i] = stepper.get_axis_position_mm((AxisEnum)i);
|
3455
|
|
-
|
3456
|
|
- #endif // !DELTA
|
|
3495
|
+ get_cartesian_from_steppers();
|
|
3496
|
+ memcpy(current_position, cartes, sizeof(cartes));
|
3457
|
3497
|
|
3458
|
3498
|
// Inform the planner about the new coordinates
|
3459
|
3499
|
SYNC_PLAN_POSITION_KINEMATIC();
|
|
@@ -3527,7 +3567,8 @@ inline void gcode_G28() {
|
3527
|
3567
|
|
3528
|
3568
|
#if ENABLED(DELTA)
|
3529
|
3569
|
// Avoid probing outside the round or hexagonal area of a delta printer
|
3530
|
|
- if (HYPOT2(xProbe, yProbe) > sq(DELTA_PROBEABLE_RADIUS) + 0.1) continue;
|
|
3570
|
+ float pos[XYZ] = { xProbe + X_PROBE_OFFSET_FROM_EXTRUDER, yProbe + Y_PROBE_OFFSET_FROM_EXTRUDER, 0 };
|
|
3571
|
+ if (!position_is_reachable(pos)) continue;
|
3531
|
3572
|
#endif
|
3532
|
3573
|
|
3533
|
3574
|
measured_z = probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level);
|
|
@@ -3839,16 +3880,21 @@ inline void gcode_G92() {
|
3839
|
3880
|
|
3840
|
3881
|
LOOP_XYZE(i) {
|
3841
|
3882
|
if (code_seen(axis_codes[i])) {
|
3842
|
|
- float p = current_position[i],
|
3843
|
|
- v = code_value_axis_units(i);
|
|
3883
|
+ #if IS_SCARA
|
|
3884
|
+ current_position[i] = code_value_axis_units(i);
|
|
3885
|
+ if (i != E_AXIS) didXYZ = true;
|
|
3886
|
+ #else
|
|
3887
|
+ float p = current_position[i],
|
|
3888
|
+ v = code_value_axis_units(i);
|
3844
|
3889
|
|
3845
|
|
- current_position[i] = v;
|
|
3890
|
+ current_position[i] = v;
|
3846
|
3891
|
|
3847
|
|
- if (i != E_AXIS) {
|
3848
|
|
- position_shift[i] += v - p; // Offset the coordinate space
|
3849
|
|
- update_software_endstops((AxisEnum)i);
|
3850
|
|
- didXYZ = true;
|
3851
|
|
- }
|
|
3892
|
+ if (i != E_AXIS) {
|
|
3893
|
+ didXYZ = true;
|
|
3894
|
+ position_shift[i] += v - p; // Offset the coordinate space
|
|
3895
|
+ update_software_endstops((AxisEnum)i);
|
|
3896
|
+ }
|
|
3897
|
+ #endif
|
3852
|
3898
|
}
|
3853
|
3899
|
}
|
3854
|
3900
|
if (didXYZ)
|
|
@@ -4196,7 +4242,8 @@ inline void gcode_M42() {
|
4196
|
4242
|
return;
|
4197
|
4243
|
}
|
4198
|
4244
|
#else
|
4199
|
|
- if (HYPOT(RAW_X_POSITION(X_probe_location), RAW_Y_POSITION(Y_probe_location)) > DELTA_PROBEABLE_RADIUS) {
|
|
4245
|
+ float pos[XYZ] = { X_probe_location, Y_probe_location, 0 };
|
|
4246
|
+ if (!position_is_reachable(pos)) {
|
4200
|
4247
|
SERIAL_PROTOCOLLNPGM("? (X,Y) location outside of probeable radius.");
|
4201
|
4248
|
return;
|
4202
|
4249
|
}
|
|
@@ -5111,20 +5158,8 @@ static void report_current_position() {
|
5111
|
5158
|
stepper.report_positions();
|
5112
|
5159
|
|
5113
|
5160
|
#if IS_SCARA
|
5114
|
|
- SERIAL_PROTOCOLPGM("SCARA Theta:");
|
5115
|
|
- SERIAL_PROTOCOL(delta[A_AXIS]);
|
5116
|
|
- SERIAL_PROTOCOLPGM(" Psi+Theta:");
|
5117
|
|
- SERIAL_PROTOCOLLN(delta[B_AXIS]);
|
5118
|
|
-
|
5119
|
|
- SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
|
5120
|
|
- SERIAL_PROTOCOL(delta[A_AXIS]);
|
5121
|
|
- SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
|
5122
|
|
- SERIAL_PROTOCOLLN(delta[B_AXIS] - delta[A_AXIS] - 90);
|
5123
|
|
-
|
5124
|
|
- SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
|
5125
|
|
- SERIAL_PROTOCOL(delta[A_AXIS] / 90 * planner.axis_steps_per_mm[A_AXIS]);
|
5126
|
|
- SERIAL_PROTOCOLPGM(" Psi+Theta:");
|
5127
|
|
- SERIAL_PROTOCOLLN((delta[B_AXIS] - delta[A_AXIS]) / 90 * planner.axis_steps_per_mm[A_AXIS]);
|
|
5161
|
+ SERIAL_PROTOCOLPAIR("SCARA Theta:", stepper.get_axis_position_mm(A_AXIS));
|
|
5162
|
+ SERIAL_PROTOCOLLNPAIR(" Psi+Theta:", stepper.get_axis_position_mm(B_AXIS));
|
5128
|
5163
|
SERIAL_EOL;
|
5129
|
5164
|
#endif
|
5130
|
5165
|
}
|
|
@@ -5346,9 +5381,9 @@ inline void gcode_M206() {
|
5346
|
5381
|
if (code_seen(axis_codes[i]))
|
5347
|
5382
|
set_home_offset((AxisEnum)i, code_value_axis_units(i));
|
5348
|
5383
|
|
5349
|
|
- #if IS_SCARA
|
5350
|
|
- if (code_seen('T')) set_home_offset(X_AXIS, code_value_axis_units(X_AXIS)); // Theta
|
5351
|
|
- if (code_seen('P')) set_home_offset(Y_AXIS, code_value_axis_units(Y_AXIS)); // Psi
|
|
5384
|
+ #if ENABLED(MORGAN_SCARA)
|
|
5385
|
+ if (code_seen('T')) set_home_offset(A_AXIS, code_value_axis_units(A_AXIS)); // Theta
|
|
5386
|
+ if (code_seen('P')) set_home_offset(B_AXIS, code_value_axis_units(B_AXIS)); // Psi
|
5352
|
5387
|
#endif
|
5353
|
5388
|
|
5354
|
5389
|
SYNC_PLAN_POSITION_KINEMATIC();
|
|
@@ -5819,10 +5854,9 @@ inline void gcode_M303() {
|
5819
|
5854
|
|
5820
|
5855
|
bool SCARA_move_to_cal(uint8_t delta_a, uint8_t delta_b) {
|
5821
|
5856
|
if (IsRunning()) {
|
5822
|
|
- //gcode_get_destination(); // For X Y Z E F
|
5823
|
5857
|
forward_kinematics_SCARA(delta_a, delta_b);
|
5824
|
|
- destination[X_AXIS] = cartes[X_AXIS];
|
5825
|
|
- destination[Y_AXIS] = cartes[Y_AXIS];
|
|
5858
|
+ destination[X_AXIS] = LOGICAL_X_POSITION(cartes[X_AXIS]);
|
|
5859
|
+ destination[Y_AXIS] = LOGICAL_Y_POSITION(cartes[Y_AXIS]);
|
5826
|
5860
|
destination[Z_AXIS] = current_position[Z_AXIS];
|
5827
|
5861
|
prepare_move_to_destination();
|
5828
|
5862
|
return true;
|
|
@@ -6976,7 +7010,11 @@ void process_next_command() {
|
6976
|
7010
|
// G0, G1
|
6977
|
7011
|
case 0:
|
6978
|
7012
|
case 1:
|
6979
|
|
- gcode_G0_G1();
|
|
7013
|
+ #if IS_SCARA
|
|
7014
|
+ gcode_G0_G1(codenum == 0);
|
|
7015
|
+ #else
|
|
7016
|
+ gcode_G0_G1();
|
|
7017
|
+ #endif
|
6980
|
7018
|
break;
|
6981
|
7019
|
|
6982
|
7020
|
// G2, G3
|
|
@@ -7777,34 +7815,38 @@ void ok_to_send() {
|
7777
|
7815
|
* - Use a fast-inverse-sqrt function and add the reciprocal.
|
7778
|
7816
|
* (see above)
|
7779
|
7817
|
*/
|
7780
|
|
- void inverse_kinematics(const float logical[XYZ]) {
|
7781
|
|
-
|
7782
|
|
- const float cartesian[XYZ] = {
|
7783
|
|
- RAW_X_POSITION(logical[X_AXIS]),
|
7784
|
|
- RAW_Y_POSITION(logical[Y_AXIS]),
|
7785
|
|
- RAW_Z_POSITION(logical[Z_AXIS])
|
7786
|
|
- };
|
7787
|
|
-
|
7788
|
|
- // Macro to obtain the Z position of an individual tower
|
7789
|
|
- #define DELTA_Z(T) cartesian[Z_AXIS] + _SQRT( \
|
7790
|
|
- delta_diagonal_rod_2_tower_##T - HYPOT2( \
|
7791
|
|
- delta_tower##T##_x - cartesian[X_AXIS], \
|
7792
|
|
- delta_tower##T##_y - cartesian[Y_AXIS] \
|
7793
|
|
- ) \
|
7794
|
|
- )
|
7795
|
7818
|
|
7796
|
|
- delta[A_AXIS] = DELTA_Z(1);
|
7797
|
|
- delta[B_AXIS] = DELTA_Z(2);
|
7798
|
|
- delta[C_AXIS] = DELTA_Z(3);
|
|
7819
|
+ // Macro to obtain the Z position of an individual tower
|
|
7820
|
+ #define DELTA_Z(T) raw[Z_AXIS] + _SQRT( \
|
|
7821
|
+ delta_diagonal_rod_2_tower_##T - HYPOT2( \
|
|
7822
|
+ delta_tower##T##_x - raw[X_AXIS], \
|
|
7823
|
+ delta_tower##T##_y - raw[Y_AXIS] \
|
|
7824
|
+ ) \
|
|
7825
|
+ )
|
|
7826
|
+
|
|
7827
|
+ #define DELTA_LOGICAL_IK() do { \
|
|
7828
|
+ const float raw[XYZ] = { \
|
|
7829
|
+ RAW_X_POSITION(logical[X_AXIS]), \
|
|
7830
|
+ RAW_Y_POSITION(logical[Y_AXIS]), \
|
|
7831
|
+ RAW_Z_POSITION(logical[Z_AXIS]) \
|
|
7832
|
+ }; \
|
|
7833
|
+ delta[A_AXIS] = DELTA_Z(1); \
|
|
7834
|
+ delta[B_AXIS] = DELTA_Z(2); \
|
|
7835
|
+ delta[C_AXIS] = DELTA_Z(3); \
|
|
7836
|
+ } while(0)
|
|
7837
|
+
|
|
7838
|
+ #define DELTA_DEBUG() do { \
|
|
7839
|
+ SERIAL_ECHOPAIR("cartesian X:", raw[X_AXIS]); \
|
|
7840
|
+ SERIAL_ECHOPAIR(" Y:", raw[Y_AXIS]); \
|
|
7841
|
+ SERIAL_ECHOLNPAIR(" Z:", raw[Z_AXIS]); \
|
|
7842
|
+ SERIAL_ECHOPAIR("delta A:", delta[A_AXIS]); \
|
|
7843
|
+ SERIAL_ECHOPAIR(" B:", delta[B_AXIS]); \
|
|
7844
|
+ SERIAL_ECHOLNPAIR(" C:", delta[C_AXIS]); \
|
|
7845
|
+ } while(0)
|
7799
|
7846
|
|
7800
|
|
- /*
|
7801
|
|
- SERIAL_ECHOPAIR("cartesian X:", cartesian[X_AXIS]);
|
7802
|
|
- SERIAL_ECHOPAIR(" Y:", cartesian[Y_AXIS]);
|
7803
|
|
- SERIAL_ECHOLNPAIR(" Z:", cartesian[Z_AXIS]);
|
7804
|
|
- SERIAL_ECHOPAIR("delta A:", delta[A_AXIS]);
|
7805
|
|
- SERIAL_ECHOPAIR(" B:", delta[B_AXIS]);
|
7806
|
|
- SERIAL_ECHOLNPAIR(" C:", delta[C_AXIS]);
|
7807
|
|
- //*/
|
|
7847
|
+ void inverse_kinematics(const float logical[XYZ]) {
|
|
7848
|
+ DELTA_LOGICAL_IK();
|
|
7849
|
+ // DELTA_DEBUG();
|
7808
|
7850
|
}
|
7809
|
7851
|
|
7810
|
7852
|
/**
|
|
@@ -7922,11 +7964,16 @@ void get_cartesian_from_steppers() {
|
7922
|
7964
|
stepper.get_axis_position_mm(B_AXIS),
|
7923
|
7965
|
stepper.get_axis_position_mm(C_AXIS)
|
7924
|
7966
|
);
|
|
7967
|
+ cartes[X_AXIS] += LOGICAL_X_POSITION(0);
|
|
7968
|
+ cartes[Y_AXIS] += LOGICAL_Y_POSITION(0);
|
|
7969
|
+ cartes[Z_AXIS] += LOGICAL_Z_POSITION(0);
|
7925
|
7970
|
#elif IS_SCARA
|
7926
|
7971
|
forward_kinematics_SCARA(
|
7927
|
7972
|
stepper.get_axis_position_degrees(A_AXIS),
|
7928
|
7973
|
stepper.get_axis_position_degrees(B_AXIS)
|
7929
|
7974
|
);
|
|
7975
|
+ cartes[X_AXIS] += LOGICAL_X_POSITION(0);
|
|
7976
|
+ cartes[Y_AXIS] += LOGICAL_Y_POSITION(0);
|
7930
|
7977
|
cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
|
7931
|
7978
|
#else
|
7932
|
7979
|
cartes[X_AXIS] = stepper.get_axis_position_mm(X_AXIS);
|
|
@@ -8026,35 +8073,134 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
|
8026
|
8073
|
* small incremental moves for DELTA or SCARA.
|
8027
|
8074
|
*/
|
8028
|
8075
|
inline bool prepare_kinematic_move_to(float logical[NUM_AXIS]) {
|
|
8076
|
+
|
|
8077
|
+ // Get the top feedrate of the move in the XY plane
|
|
8078
|
+ float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s);
|
|
8079
|
+
|
|
8080
|
+ // If the move is only in Z don't split up the move.
|
|
8081
|
+ // This shortcut cannot be used if planar bed leveling
|
|
8082
|
+ // is in use, but is fine with mesh-based bed leveling
|
|
8083
|
+ if (logical[X_AXIS] == current_position[X_AXIS] && logical[Y_AXIS] == current_position[Y_AXIS]) {
|
|
8084
|
+ inverse_kinematics(logical);
|
|
8085
|
+ planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], logical[E_AXIS], _feedrate_mm_s, active_extruder);
|
|
8086
|
+ return true;
|
|
8087
|
+ }
|
|
8088
|
+
|
|
8089
|
+ // Get the distance moved in XYZ
|
8029
|
8090
|
float difference[NUM_AXIS];
|
8030
|
8091
|
LOOP_XYZE(i) difference[i] = logical[i] - current_position[i];
|
8031
|
8092
|
|
8032
|
8093
|
float cartesian_mm = sqrt(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS]));
|
8033
|
8094
|
if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = abs(difference[E_AXIS]);
|
8034
|
8095
|
if (UNEAR_ZERO(cartesian_mm)) return false;
|
8035
|
|
- float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s);
|
|
8096
|
+
|
|
8097
|
+ // Minimum number of seconds to move the given distance
|
8036
|
8098
|
float seconds = cartesian_mm / _feedrate_mm_s;
|
8037
|
|
- int steps = max(1, int(delta_segments_per_second * seconds));
|
8038
|
|
- float inv_steps = 1.0/steps;
|
|
8099
|
+
|
|
8100
|
+ // The number of segments-per-second times the duration
|
|
8101
|
+ // gives the number of segments we should produce
|
|
8102
|
+ uint16_t segments = delta_segments_per_second * seconds;
|
|
8103
|
+
|
|
8104
|
+ #if IS_SCARA
|
|
8105
|
+ NOMORE(segments, cartesian_mm * 2);
|
|
8106
|
+ #endif
|
|
8107
|
+
|
|
8108
|
+ NOLESS(segments, 1);
|
|
8109
|
+
|
|
8110
|
+ // Each segment produces this much of the move
|
|
8111
|
+ float inv_segments = 1.0 / segments,
|
|
8112
|
+ segment_distance[XYZE] = {
|
|
8113
|
+ difference[X_AXIS] * inv_segments,
|
|
8114
|
+ difference[Y_AXIS] * inv_segments,
|
|
8115
|
+ difference[Z_AXIS] * inv_segments,
|
|
8116
|
+ difference[E_AXIS] * inv_segments
|
|
8117
|
+ };
|
8039
|
8118
|
|
8040
|
8119
|
// SERIAL_ECHOPAIR("mm=", cartesian_mm);
|
8041
|
8120
|
// SERIAL_ECHOPAIR(" seconds=", seconds);
|
8042
|
|
- // SERIAL_ECHOLNPAIR(" steps=", steps);
|
|
8121
|
+ // SERIAL_ECHOLNPAIR(" segments=", segments);
|
8043
|
8122
|
|
8044
|
|
- for (int s = 1; s <= steps; s++) {
|
|
8123
|
+ // Send all the segments to the planner
|
8045
|
8124
|
|
8046
|
|
- float fraction = float(s) * inv_steps;
|
|
8125
|
+ #if ENABLED(DELTA) && ENABLED(USE_RAW_KINEMATICS)
|
8047
|
8126
|
|
8048
|
|
- LOOP_XYZE(i)
|
8049
|
|
- logical[i] = current_position[i] + difference[i] * fraction;
|
|
8127
|
+ #define DELTA_E raw[E_AXIS]
|
|
8128
|
+ #define DELTA_NEXT(ADDEND) LOOP_XYZE(i) raw[i] += ADDEND;
|
|
8129
|
+ #define DELTA_IK() do { \
|
|
8130
|
+ delta[A_AXIS] = DELTA_Z(1); \
|
|
8131
|
+ delta[B_AXIS] = DELTA_Z(2); \
|
|
8132
|
+ delta[C_AXIS] = DELTA_Z(3); \
|
|
8133
|
+ } while(0)
|
8050
|
8134
|
|
8051
|
|
- inverse_kinematics(logical);
|
|
8135
|
+ // Get the raw current position as starting point
|
|
8136
|
+ float raw[ABC] = {
|
|
8137
|
+ RAW_CURRENT_POSITION(X_AXIS),
|
|
8138
|
+ RAW_CURRENT_POSITION(Y_AXIS),
|
|
8139
|
+ RAW_CURRENT_POSITION(Z_AXIS)
|
|
8140
|
+ };
|
8052
|
8141
|
|
8053
|
|
- //DEBUG_POS("prepare_kinematic_move_to", logical);
|
8054
|
|
- //DEBUG_POS("prepare_kinematic_move_to", delta);
|
|
8142
|
+ #else
|
|
8143
|
+
|
|
8144
|
+ #define DELTA_E logical[E_AXIS]
|
|
8145
|
+ #define DELTA_NEXT(ADDEND) LOOP_XYZE(i) logical[i] += ADDEND;
|
|
8146
|
+
|
|
8147
|
+ #if ENABLED(DELTA)
|
|
8148
|
+ #define DELTA_IK() DELTA_LOGICAL_IK()
|
|
8149
|
+ #else
|
|
8150
|
+ #define DELTA_IK() inverse_kinematics(logical)
|
|
8151
|
+ #endif
|
|
8152
|
+
|
|
8153
|
+ // Get the logical current position as starting point
|
|
8154
|
+ LOOP_XYZE(i) logical[i] = current_position[i];
|
|
8155
|
+
|
|
8156
|
+ #endif
|
|
8157
|
+
|
|
8158
|
+ #if ENABLED(USE_DELTA_IK_INTERPOLATION)
|
|
8159
|
+
|
|
8160
|
+ // Get the starting delta for interpolation
|
|
8161
|
+ if (segments >= 2) inverse_kinematics(logical);
|
|
8162
|
+
|
|
8163
|
+ for (uint16_t s = segments + 1; --s;) {
|
|
8164
|
+ if (s > 1) {
|
|
8165
|
+ // Save the previous delta for interpolation
|
|
8166
|
+ float prev_delta[ABC] = { delta[A_AXIS], delta[B_AXIS], delta[C_AXIS] };
|
|
8167
|
+
|
|
8168
|
+ // Get the delta 2 segments ahead (rather than the next)
|
|
8169
|
+ DELTA_NEXT(segment_distance[i] + segment_distance[i]);
|
|
8170
|
+ DELTA_IK();
|
|
8171
|
+
|
|
8172
|
+ // Move to the interpolated delta position first
|
|
8173
|
+ planner.buffer_line(
|
|
8174
|
+ (prev_delta[A_AXIS] + delta[A_AXIS]) * 0.5,
|
|
8175
|
+ (prev_delta[B_AXIS] + delta[B_AXIS]) * 0.5,
|
|
8176
|
+ (prev_delta[C_AXIS] + delta[C_AXIS]) * 0.5,
|
|
8177
|
+ logical[E_AXIS], _feedrate_mm_s, active_extruder
|
|
8178
|
+ );
|
|
8179
|
+
|
|
8180
|
+ // Do an extra decrement of the loop
|
|
8181
|
+ --s;
|
|
8182
|
+ }
|
|
8183
|
+ else {
|
|
8184
|
+ // Get the last segment delta (only when segments is odd)
|
|
8185
|
+ DELTA_NEXT(segment_distance[i])
|
|
8186
|
+ DELTA_IK();
|
|
8187
|
+ }
|
|
8188
|
+
|
|
8189
|
+ // Move to the non-interpolated position
|
|
8190
|
+ planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], DELTA_E, _feedrate_mm_s, active_extruder);
|
|
8191
|
+ }
|
|
8192
|
+
|
|
8193
|
+ #else
|
|
8194
|
+
|
|
8195
|
+ // For non-interpolated delta calculate every segment
|
|
8196
|
+ for (uint16_t s = segments + 1; --s;) {
|
|
8197
|
+ DELTA_NEXT(segment_distance[i])
|
|
8198
|
+ DELTA_IK();
|
|
8199
|
+ planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], logical[E_AXIS], _feedrate_mm_s, active_extruder);
|
|
8200
|
+ }
|
|
8201
|
+
|
|
8202
|
+ #endif
|
8055
|
8203
|
|
8056
|
|
- planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], logical[E_AXIS], _feedrate_mm_s, active_extruder);
|
8057
|
|
- }
|
8058
|
8204
|
return true;
|
8059
|
8205
|
}
|
8060
|
8206
|
|
|
@@ -8371,25 +8517,26 @@ void prepare_move_to_destination() {
|
8371
|
8517
|
|
8372
|
8518
|
#endif // HAS_CONTROLLERFAN
|
8373
|
8519
|
|
8374
|
|
-#if IS_SCARA
|
|
8520
|
+#if ENABLED(MORGAN_SCARA)
|
8375
|
8521
|
|
|
8522
|
+ /**
|
|
8523
|
+ * Morgan SCARA Forward Kinematics. Results in cartes[].
|
|
8524
|
+ * Maths and first version by QHARLEY.
|
|
8525
|
+ * Integrated into Marlin and slightly restructured by Joachim Cerny.
|
|
8526
|
+ */
|
8376
|
8527
|
void forward_kinematics_SCARA(const float &a, const float &b) {
|
8377
|
|
- // Perform forward kinematics, and place results in cartes[]
|
8378
|
|
- // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
|
8379
|
8528
|
|
8380
|
|
- float a_sin, a_cos, b_sin, b_cos;
|
8381
|
|
-
|
8382
|
|
- a_sin = sin(RADIANS(a)) * L1;
|
8383
|
|
- a_cos = cos(RADIANS(a)) * L1;
|
8384
|
|
- b_sin = sin(RADIANS(b)) * L2;
|
8385
|
|
- b_cos = cos(RADIANS(b)) * L2;
|
|
8529
|
+ float a_sin = sin(RADIANS(a)) * L1,
|
|
8530
|
+ a_cos = cos(RADIANS(a)) * L1,
|
|
8531
|
+ b_sin = sin(RADIANS(b)) * L2,
|
|
8532
|
+ b_cos = cos(RADIANS(b)) * L2;
|
8386
|
8533
|
|
8387
|
8534
|
cartes[X_AXIS] = a_cos + b_cos + SCARA_OFFSET_X; //theta
|
8388
|
8535
|
cartes[Y_AXIS] = a_sin + b_sin + SCARA_OFFSET_Y; //theta+phi
|
8389
|
8536
|
|
8390
|
8537
|
/*
|
8391
|
|
- SERIAL_ECHOPAIR("f_delta x=", a);
|
8392
|
|
- SERIAL_ECHOPAIR(" y=", b);
|
|
8538
|
+ SERIAL_ECHOPAIR("Angle a=", a);
|
|
8539
|
+ SERIAL_ECHOPAIR(" b=", b);
|
8393
|
8540
|
SERIAL_ECHOPAIR(" a_sin=", a_sin);
|
8394
|
8541
|
SERIAL_ECHOPAIR(" a_cos=", a_cos);
|
8395
|
8542
|
SERIAL_ECHOPAIR(" b_sin=", b_sin);
|
|
@@ -8399,29 +8546,38 @@ void prepare_move_to_destination() {
|
8399
|
8546
|
//*/
|
8400
|
8547
|
}
|
8401
|
8548
|
|
|
8549
|
+ /**
|
|
8550
|
+ * Morgan SCARA Inverse Kinematics. Results in delta[].
|
|
8551
|
+ *
|
|
8552
|
+ * See http://forums.reprap.org/read.php?185,283327
|
|
8553
|
+ *
|
|
8554
|
+ * Maths and first version by QHARLEY.
|
|
8555
|
+ * Integrated into Marlin and slightly restructured by Joachim Cerny.
|
|
8556
|
+ */
|
8402
|
8557
|
void inverse_kinematics(const float logical[XYZ]) {
|
8403
|
|
- // Inverse kinematics.
|
8404
|
|
- // Perform SCARA IK and place results in delta[].
|
8405
|
|
- // The maths and first version were done by QHARLEY.
|
8406
|
|
- // Integrated, tweaked by Joachim Cerny in June 2014.
|
8407
|
8558
|
|
8408
|
8559
|
static float C2, S2, SK1, SK2, THETA, PSI;
|
8409
|
8560
|
|
8410
|
8561
|
float sx = RAW_X_POSITION(logical[X_AXIS]) - SCARA_OFFSET_X, // Translate SCARA to standard X Y
|
8411
|
8562
|
sy = RAW_Y_POSITION(logical[Y_AXIS]) - SCARA_OFFSET_Y; // With scaling factor.
|
8412
|
8563
|
|
8413
|
|
- #if (L1 == L2)
|
8414
|
|
- C2 = HYPOT2(sx, sy) / (2 * L1_2) - 1;
|
8415
|
|
- #else
|
8416
|
|
- C2 = (HYPOT2(sx, sy) - L1_2 - L2_2) / 45000;
|
8417
|
|
- #endif
|
|
8564
|
+ if (L1 == L2)
|
|
8565
|
+ C2 = HYPOT2(sx, sy) / L1_2_2 - 1;
|
|
8566
|
+ else
|
|
8567
|
+ C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2);
|
8418
|
8568
|
|
8419
|
|
- S2 = sqrt(1 - sq(C2));
|
|
8569
|
+ S2 = sqrt(sq(C2) - 1);
|
8420
|
8570
|
|
|
8571
|
+ // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
|
8421
|
8572
|
SK1 = L1 + L2 * C2;
|
|
8573
|
+
|
|
8574
|
+ // Rotated Arm2 gives the distance from Arm1 to Arm2
|
8422
|
8575
|
SK2 = L2 * S2;
|
8423
|
8576
|
|
8424
|
|
- THETA = (atan2(sx, sy) - atan2(SK1, SK2)) * -1;
|
|
8577
|
+ // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
|
|
8578
|
+ THETA = atan2(SK1, SK2) - atan2(sx, sy);
|
|
8579
|
+
|
|
8580
|
+ // Angle of Arm2
|
8425
|
8581
|
PSI = atan2(S2, C2);
|
8426
|
8582
|
|
8427
|
8583
|
delta[A_AXIS] = DEGREES(THETA); // theta is support arm angle
|
|
@@ -8440,7 +8596,7 @@ void prepare_move_to_destination() {
|
8440
|
8596
|
//*/
|
8441
|
8597
|
}
|
8442
|
8598
|
|
8443
|
|
-#endif // IS_SCARA
|
|
8599
|
+#endif // MORGAN_SCARA
|
8444
|
8600
|
|
8445
|
8601
|
#if ENABLED(TEMP_STAT_LEDS)
|
8446
|
8602
|
|