Kaynağa Gözat

Mostly Printed SCARA (MPSCARA) support (#15573)

brian park 5 yıl önce
ebeveyn
işleme
b258cc85bf

+ 1
- 0
Marlin/src/core/macros.h Dosyayı Görüntüle

@@ -251,6 +251,7 @@
251 251
 //
252 252
 // Maths macros that can be overridden by HAL
253 253
 //
254
+#define ACOS(x)     acosf(x)
254 255
 #define ATAN2(y, x) atan2f(y, x)
255 256
 #define POW(x, y)   powf(x, y)
256 257
 #define SQRT(x)     sqrtf(x)

+ 63
- 44
Marlin/src/module/scara.cpp Dosyayı Görüntüle

@@ -45,19 +45,19 @@ void scara_set_axis_is_at_home(const AxisEnum axis) {
45 45
     xyz_pos_t homeposition;
46 46
     LOOP_XYZ(i) homeposition[i] = base_home_pos((AxisEnum)i);
47 47
 
48
-    // SERIAL_ECHOLNPAIR("homeposition X:", homeposition.x, " Y:", homeposition.y);
49
-
50
-    /**
51
-     * Get Home position SCARA arm angles using inverse kinematics,
52
-     * and calculate homing offset using forward kinematics
53
-     */
54
-    inverse_kinematics(homeposition);
55
-    forward_kinematics_SCARA(delta.a, delta.b);
56
-
57
-    // SERIAL_ECHOLNPAIR("Cartesian X:", cartes.x, " Y:", cartes.y);
58
-
59
-    current_position[axis] = cartes[axis];
60
-
48
+    #if ENABLED(MORGAN_SCARA)
49
+      // MORGAN_SCARA uses arm angles for AB home position
50
+      // SERIAL_ECHOLNPAIR("homeposition A:", homeposition.a, " B:", homeposition.b);
51
+      inverse_kinematics(homeposition);
52
+      forward_kinematics_SCARA(delta.a, delta.b);
53
+      current_position[axis] = cartes[axis];
54
+    #else
55
+      // MP_SCARA uses a Cartesian XY home position
56
+      // SERIAL_ECHOLNPAIR("homeposition X:", homeposition.x, " Y:", homeposition.y);
57
+      current_position[axis] = homeposition[axis];
58
+    #endif
59
+
60
+    // SERIAL_ECHOLNPAIR("Cartesian X:", current_position.x, " Y:", current_position.y);
61 61
     update_software_endstops(axis);
62 62
   }
63 63
 }
@@ -92,48 +92,67 @@ void forward_kinematics_SCARA(const float &a, const float &b) {
92 92
   //*/
93 93
 }
94 94
 
95
-/**
96
- * Morgan SCARA Inverse Kinematics. Results in 'delta'.
97
- *
98
- * See http://forums.reprap.org/read.php?185,283327
99
- *
100
- * Maths and first version by QHARLEY.
101
- * Integrated into Marlin and slightly restructured by Joachim Cerny.
102
- */
103 95
 void inverse_kinematics(const xyz_pos_t &raw) {
104 96
 
105
-  float C2, S2, SK1, SK2, THETA, PSI;
97
+  #if ENABLED(MORGAN_SCARA)
98
+  
99
+    /**
100
+     * Morgan SCARA Inverse Kinematics. Results in 'delta'.
101
+     *
102
+     * See http://forums.reprap.org/read.php?185,283327
103
+     *
104
+     * Maths and first version by QHARLEY.
105
+     * Integrated into Marlin and slightly restructured by Joachim Cerny.
106
+     */
107
+    float C2, S2, SK1, SK2, THETA, PSI;
106 108
 
107
-  // Translate SCARA to standard XY with scaling factor
108
-  const xy_pos_t spos = raw - scara_offset;
109
+    // Translate SCARA to standard XY with scaling factor
110
+    const xy_pos_t spos = raw - scara_offset;
109 111
 
110
-  const float H2 = HYPOT2(spos.x, spos.y);
111
-  if (L1 == L2)
112
-    C2 = H2 / L1_2_2 - 1;
113
-  else
114
-    C2 = (H2 - (L1_2 + L2_2)) / (2.0 * L1 * L2);
112
+    const float H2 = HYPOT2(spos.x, spos.y);
113
+    if (L1 == L2)
114
+      C2 = H2 / L1_2_2 - 1;
115
+    else
116
+      C2 = (H2 - (L1_2 + L2_2)) / (2.0f * L1 * L2);
115 117
 
116
-  S2 = SQRT(1.0f - sq(C2));
118
+    S2 = SQRT(1.0f - sq(C2));
117 119
 
118
-  // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
119
-  SK1 = L1 + L2 * C2;
120
+    // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
121
+    SK1 = L1 + L2 * C2;
120 122
 
121
-  // Rotated Arm2 gives the distance from Arm1 to Arm2
122
-  SK2 = L2 * S2;
123
+    // Rotated Arm2 gives the distance from Arm1 to Arm2
124
+    SK2 = L2 * S2;
123 125
 
124
-  // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
125
-  THETA = ATAN2(SK1, SK2) - ATAN2(spos.x, spos.y);
126
+    // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
127
+    THETA = ATAN2(SK1, SK2) - ATAN2(spos.x, spos.y);
126 128
 
127
-  // Angle of Arm2
128
-  PSI = ATAN2(S2, C2);
129
+    // Angle of Arm2
130
+    PSI = ATAN2(S2, C2);
129 131
 
130
-  delta.set(DEGREES(THETA), DEGREES(THETA + PSI), raw.z);
132
+    delta.set(DEGREES(THETA), DEGREES(THETA + PSI), raw.z);
131 133
 
132
-  /*
133
-    DEBUG_POS("SCARA IK", raw);
134
-    DEBUG_POS("SCARA IK", delta);
135
-    SERIAL_ECHOLNPAIR("  SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Phi=", PHI);
136
-  //*/
134
+    /*
135
+      DEBUG_POS("SCARA IK", raw);
136
+      DEBUG_POS("SCARA IK", delta);
137
+      SERIAL_ECHOLNPAIR("  SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Phi=", PHI);
138
+    //*/
139
+
140
+  #else // MP_SCARA
141
+
142
+    const float x = raw.x, y = raw.y, c = HYPOT(x, y),
143
+                THETA3 = ATAN2(y, x),
144
+                THETA1 = THETA3 + ACOS((sq(c) + sq(L1) - sq(L2)) / (2.0f * c * L1)),
145
+                THETA2 = THETA3 - ACOS((sq(c) + sq(L2) - sq(L1)) / (2.0f * c * L2));
146
+
147
+    delta.set(DEGREES(THETA1), DEGREES(THETA2), raw.z);
148
+
149
+    /*
150
+      DEBUG_POS("SCARA IK", raw);
151
+      DEBUG_POS("SCARA IK", delta);
152
+      SERIAL_ECHOLNPAIR("  SCARA (x,y) ", x, ",", y," Theta1=", THETA1, " Theta2=", THETA2);
153
+    //*/
154
+
155
+  #endif // MP_SCARA
137 156
 }
138 157
 
139 158
 void scara_report_positions() {

+ 2245
- 0
config/examples/SCARA/MP_SCARA/Configuration.h
Dosya farkı çok büyük olduğundan ihmal edildi
Dosyayı Görüntüle


+ 2756
- 0
config/examples/SCARA/MP_SCARA/Configuration_adv.h
Dosya farkı çok büyük olduğundan ihmal edildi
Dosyayı Görüntüle


config/examples/SCARA/Configuration.h → config/examples/SCARA/Morgan/Configuration.h Dosyayı Görüntüle

@@ -62,32 +62,45 @@
62 62
  * MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013.
63 63
  * Implemented and slightly reworked by JCERNY in June, 2014.
64 64
  */
65
-
66
-// Specify the specific SCARA model
67 65
 #define MORGAN_SCARA
68 66
 
69
-#if ENABLED(MORGAN_SCARA)
70
-
71
-  //#define DEBUG_SCARA_KINEMATICS
72
-  #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly
67
+/**
68
+ * Mostly Printed SCARA is an open source design by Tyler Williams. See:
69
+ *   https://www.thingiverse.com/thing:2487048
70
+ *   https://www.thingiverse.com/thing:1241491
71
+ */
72
+//#define MP_SCARA
73 73
 
74
+#if EITHER(MORGAN_SCARA, MP_SCARA)
74 75
   // If movement is choppy try lowering this value
75 76
   #define SCARA_SEGMENTS_PER_SECOND 200
76 77
 
77 78
   // Length of inner and outer support arms. Measure arm lengths precisely.
78
-  #define SCARA_LINKAGE_1 150 //mm
79
-  #define SCARA_LINKAGE_2 150 //mm
79
+  #define SCARA_LINKAGE_1 150       // (mm)
80
+  #define SCARA_LINKAGE_2 150       // (mm)
80 81
 
81 82
   // SCARA tower offset (position of Tower relative to bed zero position)
82 83
   // This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
83
-  #define SCARA_OFFSET_X 100 //mm
84
-  #define SCARA_OFFSET_Y -56 //mm
84
+  #define SCARA_OFFSET_X  100       // (mm)
85
+  #define SCARA_OFFSET_Y  -56       // (mm)
86
+
87
+  #if ENABLED(MORGAN_SCARA)
85 88
 
86
-  // Radius around the center where the arm cannot reach
87
-  #define MIDDLE_DEAD_ZONE_R 0 //mm
89
+    //#define DEBUG_SCARA_KINEMATICS
90
+    #define SCARA_FEEDRATE_SCALING  // Convert XY feedrate from mm/s to degrees/s on the fly
88 91
 
89
-  #define THETA_HOMING_OFFSET 0  //calculatated from Calibration Guide and command M360 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
90
-  #define PSI_HOMING_OFFSET   0  //calculatated from Calibration Guide and command M364 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
92
+    // Radius around the center where the arm cannot reach
93
+    #define MIDDLE_DEAD_ZONE_R   0  // (mm)
94
+
95
+    #define THETA_HOMING_OFFSET  0  // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073
96
+    #define PSI_HOMING_OFFSET    0  // Calculated from Calibration Guide and M364 / M114. See http://reprap.harleystudio.co.za/?page_id=1073
97
+
98
+  #elif ENABLED(MP_SCARA)
99
+
100
+    #define SCARA_OFFSET_THETA1  12 // degrees
101
+    #define SCARA_OFFSET_THETA2 131 // degrees
102
+
103
+  #endif
91 104
 
92 105
 #endif
93 106
 

config/examples/SCARA/Configuration_adv.h → config/examples/SCARA/Morgan/Configuration_adv.h Dosyayı Görüntüle


Loading…
İptal
Kaydet