Browse Source

Patch SCARA example config

Scott Lahteine 8 years ago
parent
commit
74d7f5e57b
3 changed files with 63 additions and 67 deletions
  1. 32
    41
      Marlin/Marlin_main.cpp
  2. 6
    3
      Marlin/SanityCheck.h
  3. 25
    23
      Marlin/example_configurations/SCARA/Configuration.h

+ 32
- 41
Marlin/Marlin_main.cpp View File

@@ -8457,18 +8457,18 @@ void prepare_move_to_destination() {
8457 8457
     //SERIAL_ECHOPGM("f_delta x="); SERIAL_ECHO(f_scara[X_AXIS]);
8458 8458
     //SERIAL_ECHOPGM(" y="); SERIAL_ECHO(f_scara[Y_AXIS]);
8459 8459
 
8460
-    x_sin = sin(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1;
8461
-    x_cos = cos(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1;
8462
-    y_sin = sin(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2;
8463
-    y_cos = cos(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2;
8460
+    x_sin = sin(RADIANS(f_scara[X_AXIS])) * L1;
8461
+    x_cos = cos(RADIANS(f_scara[X_AXIS])) * L1;
8462
+    y_sin = sin(RADIANS(f_scara[Y_AXIS])) * L2;
8463
+    y_cos = cos(RADIANS(f_scara[Y_AXIS])) * L2;
8464 8464
 
8465 8465
     //SERIAL_ECHOPGM(" x_sin="); SERIAL_ECHO(x_sin);
8466 8466
     //SERIAL_ECHOPGM(" x_cos="); SERIAL_ECHO(x_cos);
8467 8467
     //SERIAL_ECHOPGM(" y_sin="); SERIAL_ECHO(y_sin);
8468 8468
     //SERIAL_ECHOPGM(" y_cos="); SERIAL_ECHOLN(y_cos);
8469 8469
 
8470
-    delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x;  //theta
8471
-    delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y;  //theta+phi
8470
+    delta[X_AXIS] = x_cos + y_cos + SCARA_OFFSET_X;  //theta
8471
+    delta[Y_AXIS] = x_sin + y_sin + SCARA_OFFSET_Y;  //theta+phi
8472 8472
 
8473 8473
     //SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]);
8474 8474
     //SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
@@ -8480,51 +8480,42 @@ void prepare_move_to_destination() {
8480 8480
     // The maths and first version were done by QHARLEY.
8481 8481
     // Integrated, tweaked by Joachim Cerny in June 2014.
8482 8482
 
8483
-    float SCARA_pos[2];
8484
-    static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi;
8483
+    static float C2, S2, SK1, SK2, THETA, PSI;
8485 8484
 
8486
-    SCARA_pos[X_AXIS] = RAW_X_POSITION(cartesian[X_AXIS]) * axis_scaling[X_AXIS] - SCARA_offset_x;  //Translate SCARA to standard X Y
8487
-    SCARA_pos[Y_AXIS] = RAW_Y_POSITION(cartesian[Y_AXIS]) * axis_scaling[Y_AXIS] - SCARA_offset_y;  // With scaling factor.
8485
+    float sx = RAW_X_POSITION(cartesian[X_AXIS]) * axis_scaling[X_AXIS] - SCARA_OFFSET_X,  //Translate SCARA to standard X Y
8486
+          sy = RAW_Y_POSITION(cartesian[Y_AXIS]) * axis_scaling[Y_AXIS] - SCARA_OFFSET_Y;  // With scaling factor.
8488 8487
 
8489
-    #if (Linkage_1 == Linkage_2)
8490
-      SCARA_C2 = ((sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS])) / (2 * (float)L1_2)) - 1;
8488
+    #if (L1 == L2)
8489
+      C2 = HYPOT2(sx, sy) / (2 * L1_2) - 1;
8491 8490
     #else
8492
-      SCARA_C2 = (sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2) / 45000;
8491
+      C2 = (HYPOT2(sx, sy) - L1_2 - L2_2) / 45000;
8493 8492
     #endif
8494 8493
 
8495
-    SCARA_S2 = sqrt(1 - sq(SCARA_C2));
8494
+    S2 = sqrt(1 - sq(C2));
8496 8495
 
8497
-    SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2;
8498
-    SCARA_K2 = Linkage_2 * SCARA_S2;
8496
+    SK1 = L1 + L2 * C2;
8497
+    SK2 = L2 * S2;
8499 8498
 
8500
-    SCARA_theta = (atan2(SCARA_pos[X_AXIS], SCARA_pos[Y_AXIS]) - atan2(SCARA_K1, SCARA_K2)) * -1;
8501
-    SCARA_psi = atan2(SCARA_S2, SCARA_C2);
8499
+    THETA = (atan2(sx, sy) - atan2(SK1, SK2)) * -1;
8500
+    PSI = atan2(S2, C2);
8502 8501
 
8503
-    delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG;  // Multiply by 180/Pi  -  theta is support arm angle
8504
-    delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG;  //       -  equal to sub arm angle (inverted motor)
8505
-    delta[Z_AXIS] = RAW_Z_POSITION(cartesian[Z_AXIS]);
8502
+    delta[A_AXIS] = DEGREES(THETA);        // theta is support arm angle
8503
+    delta[B_AXIS] = DEGREES(THETA + PSI);  // equal to sub arm angle (inverted motor)
8504
+    delta[Z_AXIS] = cartesian[Z_AXIS];
8506 8505
 
8507 8506
     /**
8508
-    SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
8509
-    SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
8510
-    SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
8511
-
8512
-    SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]);
8513
-    SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]);
8514
-
8515
-    SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
8516
-    SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
8517
-    SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
8518
-
8519
-    SERIAL_ECHOPGM("C2="); SERIAL_ECHO(SCARA_C2);
8520
-    SERIAL_ECHOPGM(" S2="); SERIAL_ECHO(SCARA_S2);
8521
-    SERIAL_ECHOPGM(" Theta="); SERIAL_ECHO(SCARA_theta);
8522
-    SERIAL_ECHOPGM(" Psi="); SERIAL_ECHOLN(SCARA_psi);
8523
-    SERIAL_EOL;
8524
-    */
8525
-  }
8526
-
8527
-#endif // SCARA
8507
+      DEBUG_POS("SCARA IK", cartesian);
8508
+      DEBUG_POS("SCARA IK", delta);
8509
+      SERIAL_ECHOPAIR("  SCARA (x,y) ", sx);
8510
+      SERIAL_ECHOPAIR(",", sy);
8511
+      SERIAL_ECHOPAIR(" C2=", C2);
8512
+      SERIAL_ECHOPAIR(" S2=", S2);
8513
+      SERIAL_ECHOPAIR(" Theta=", THETA);
8514
+      SERIAL_ECHOLNPAIR(" Phi=", PHI);
8515
+    //*/
8516
+  }
8517
+
8518
+#endif // MORGAN_SCARA
8528 8519
 
8529 8520
 #if ENABLED(TEMP_STAT_LEDS)
8530 8521
 

+ 6
- 3
Marlin/SanityCheck.h View File

@@ -137,6 +137,8 @@
137 137
   #error Please replace "const int dropsegments" with "#define MIN_STEPS_PER_SEGMENT" (and increase by 1) in Configuration_adv.h.
138 138
 #elif defined(PREVENT_DANGEROUS_EXTRUDE)
139 139
   #error "PREVENT_DANGEROUS_EXTRUDE is now PREVENT_COLD_EXTRUSION. Please update your configuration."
140
+#elif defined(SCARA)
141
+  #error "SCARA is now MORGAN_SCARA. Please update your configuration."
140 142
 #endif
141 143
 
142 144
 /**
@@ -573,11 +575,12 @@
573 575
 /**
574 576
  * Don't set more than one kinematic type
575 577
  */
576
-#if (ENABLED(DELTA) && (ENABLED(SCARA) || ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ))) \
578
+#if (ENABLED(DELTA) && (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA) || ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ))) \
579
+ || (ENABLED(DELTA) && (ENABLED(MAKERARM_SCARA) || ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ))) \
577 580
  || (ENABLED(SCARA) && (ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ))) \
578 581
  || (ENABLED(COREXY) && (ENABLED(COREXZ) || ENABLED(COREYZ))) \
579 582
  || (ENABLED(COREXZ) && ENABLED(COREYZ))
580
-  #error "Please enable only one of DELTA, SCARA, COREXY, COREXZ, or COREYZ."
583
+  #error "Please enable only one of DELTA, MORGAN_SCARA, MAKERARM_SCARA, COREXY, COREXZ, or COREYZ."
581 584
 #endif
582 585
 
583 586
 /**
@@ -750,7 +753,7 @@
750 753
   #elif ENABLED(DELTA)
751 754
     #error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
752 755
   #endif
753
-#elif DISABLED(SCARA)
756
+#elif !IS_SCARA
754 757
   #if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG)
755 758
     #error "Enable USE_XMIN_PLUG when homing X to MIN."
756 759
   #elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG)

+ 25
- 23
Marlin/example_configurations/SCARA/Configuration.h View File

@@ -75,35 +75,37 @@
75 75
 //
76 76
 
77 77
 //===========================================================================
78
-//========================= SCARA Settings ==================================
78
+//============================= SCARA Printer ===============================
79 79
 //===========================================================================
80
-// SCARA-mode for Marlin has been developed by QHARLEY in ZA in 2012/2013. Implemented
80
+// MORGAN_SCARA for Marlin was developed by QHARLEY in ZA in 2012/2013. Implemented
81 81
 // and slightly reworked by JCERNY in 06/2014 with the goal to bring it into Master-Branch
82 82
 // QHARLEYS Autobedlevelling has not been ported, because Marlin has now Bed-levelling
83 83
 // You might need Z-Min endstop on SCARA-Printer to use this feature. Actually untested!
84
-// Uncomment to use Morgan scara mode
85
-#define SCARA
86
-#define SCARA_SEGMENTS_PER_SECOND 200 // If movement is choppy try lowering this value
87
-// Length of inner support arm
88
-#define Linkage_1 150 //mm      Preprocessor cannot handle decimal point...
89
-// Length of outer support arm     Measure arm lengths precisely and enter
90
-#define Linkage_2 150 //mm
91
-
92
-// SCARA tower offset (position of Tower relative to bed zero position)
93
-// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
94
-#define SCARA_offset_x 100 //mm
95
-#define SCARA_offset_y -56 //mm
96
-#define SCARA_RAD2DEG 57.2957795  // to convert RAD to degrees
97
-
98
-#define THETA_HOMING_OFFSET 0  //calculatated from Calibration Guide and command M360 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
99
-#define PSI_HOMING_OFFSET   0  //calculatated from Calibration Guide and command M364 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
100
-
101
-//some helper variables to make kinematics faster
102
-#define L1_2 sq(Linkage_1) // do not change
103
-#define L2_2 sq(Linkage_2) // do not change
84
+
85
+// Specify the specific SCARA model
86
+#define MORGAN_SCARA
87
+//#define MAKERARM_SCARA
88
+
89
+#if ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA)
90
+  //#define DEBUG_SCARA_KINEMATICS
91
+
92
+  #define SCARA_SEGMENTS_PER_SECOND 200 // If movement is choppy try lowering this value
93
+  // Length of inner support arm
94
+  #define SCARA_LINKAGE_1 150 //mm      Preprocessor cannot handle decimal point...
95
+  // Length of outer support arm     Measure arm lengths precisely and enter
96
+  #define SCARA_LINKAGE_2 150 //mm
97
+
98
+  // SCARA tower offset (position of Tower relative to bed zero position)
99
+  // This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
100
+  #define SCARA_OFFSET_X 100 //mm
101
+  #define SCARA_OFFSET_Y -56 //mm
102
+
103
+  #define THETA_HOMING_OFFSET 0  //calculatated from Calibration Guide and command M360 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
104
+  #define PSI_HOMING_OFFSET   0  //calculatated from Calibration Guide and command M364 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
105
+#endif
104 106
 
105 107
 //===========================================================================
106
-//========================= SCARA Settings end ==============================
108
+//==================== END ==== SCARA Printer ==== END ======================
107 109
 //===========================================================================
108 110
 
109 111
 // @section info

Loading…
Cancel
Save