Skip to content

Commit 174ecae

Browse files
committed
✨ Generic "Standard" SCARA
MarlinFirmware/Marlin#28357
1 parent 539fda0 commit 174ecae

413 files changed

Lines changed: 15620 additions & 9045 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

config/default/Configuration.h

Lines changed: 38 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1015,7 +1015,9 @@
10151015

10161016
// @section polargraph
10171017

1018-
// Enable for Polargraph Kinematics
1018+
/**
1019+
* Polargraph Kinematics
1020+
*/
10191021
//#define POLARGRAPH
10201022
#if ENABLED(POLARGRAPH)
10211023
#define POLARGRAPH_MAX_BELT_LEN 1035.0 // (mm) Belt length at full extension. Override with M665 H.
@@ -1025,7 +1027,9 @@
10251027

10261028
// @section delta
10271029

1028-
// Enable for DELTA kinematics and configure below
1030+
/**
1031+
* DELTA kinematics
1032+
*/
10291033
//#define DELTA
10301034
#if ENABLED(DELTA)
10311035

@@ -1083,44 +1087,56 @@
10831087
// @section scara
10841088

10851089
/**
1086-
* MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013.
1090+
* SCARA kinematics
1091+
*
1092+
* - Positive angles rotate counterclockwise when looking down from above.
1093+
* - Theta is the shoulder angle. 0 degrees aligns to Cartesian positive X.
1094+
* - Psi is the elbow angle. 0° is straight, ±180° is completely folded (right-handed positive, left-handed negative).
1095+
*
1096+
* The Morgan SCARA was developed by QHARLEY in South Africa in 2012-2013.
10871097
* Implemented and slightly reworked by JCERNY in June, 2014.
10881098
*
10891099
* Mostly Printed SCARA is an open source design by Tyler Williams. See:
10901100
* https://www.thingiverse.com/thing:2487048
10911101
* https://www.thingiverse.com/thing:1241491
10921102
*/
1093-
//#define MORGAN_SCARA
1094-
//#define MP_SCARA
1095-
#if ANY(MORGAN_SCARA, MP_SCARA)
1103+
1104+
//#define SCARA
1105+
#if ENABLED(SCARA)
10961106
// If movement is choppy try lowering this value
10971107
#define DEFAULT_SEGMENTS_PER_SECOND 200
10981108

10991109
// Length of inner and outer support arms. Measure arm lengths precisely.
1100-
#define SCARA_LINKAGE_1 150 // (mm)
1101-
#define SCARA_LINKAGE_2 150 // (mm)
1110+
#define SCARA_LINKAGE_1 135 // (mm)
1111+
#define SCARA_LINKAGE_2 135 // (mm)
11021112

1103-
// SCARA tower offset (position of Tower relative to bed zero position)
1113+
// SCARA tower offset (position of shoulder axis relative to bed zero position)
11041114
// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
1105-
#define SCARA_OFFSET_X 100 // (mm)
1106-
#define SCARA_OFFSET_Y -56 // (mm)
1115+
#define SCARA_OFFSET_X 0 // (mm)
1116+
#define SCARA_OFFSET_Y -150 // (mm)
11071117

1108-
#if ENABLED(MORGAN_SCARA)
1118+
// Radius of unreachable area near shoulder axis
1119+
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
11091120

1110-
//#define DEBUG_SCARA_KINEMATICS
1111-
#define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly
1121+
// Direction of elbow bend. 1 = right-handed (counterclockwise), -1 = left-handed (clockwise)
1122+
#define SCARA_ELBOW_DIR 1
11121123

1113-
// Radius around the center where the arm cannot reach
1114-
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
1124+
// This defines how shoulder movement affects the distal arm angle. Common values:
1125+
// 0.0 if distal arm retains its angle relative to proximal arm (e.g. if elbow motor rides on proximal arm)
1126+
// 1.0 if distal arm retains its angle relative to cartesian X axis (e.g. Morgan and MPSCARA)
1127+
// A two-stage reduction with an intermediate pulley on the shoulder axis has crosstalk =
1128+
// intermediate_pulley_teeth/elbow_pulley_teeth (first reduction stage does not affect crosstalk)
1129+
#define SCARA_CROSSTALK_FACTOR (40.0/60.0)
11151130

1116-
#elif ENABLED(MP_SCARA)
1131+
// Shoulder and elbow angles when in home position. If left undefined, cartesian home is used and
1132+
// angles are calculated by inverse kinematics (note: M665 home offsets are still angles)
1133+
#define SCARA_HOME_THETA -40
1134+
#define SCARA_HOME_PSI 160
11171135

1118-
#define SCARA_OFFSET_THETA1 12 // degrees
1119-
#define SCARA_OFFSET_THETA2 131 // degrees
1136+
// Enable M360-M364 to calibrate SCARA angles
1137+
//#define SCARA_CALIBRATION
11201138

1121-
#endif
1122-
1123-
#endif
1139+
#endif // SCARA
11241140

11251141
// @section tpara
11261142

config/examples/3DFabXYZ/Migbot/Configuration.h

Lines changed: 38 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1017,7 +1017,9 @@
10171017

10181018
// @section polargraph
10191019

1020-
// Enable for Polargraph Kinematics
1020+
/**
1021+
* Polargraph Kinematics
1022+
*/
10211023
//#define POLARGRAPH
10221024
#if ENABLED(POLARGRAPH)
10231025
#define POLARGRAPH_MAX_BELT_LEN 1035.0 // (mm) Belt length at full extension. Override with M665 H.
@@ -1027,7 +1029,9 @@
10271029

10281030
// @section delta
10291031

1030-
// Enable for DELTA kinematics and configure below
1032+
/**
1033+
* DELTA kinematics
1034+
*/
10311035
//#define DELTA
10321036
#if ENABLED(DELTA)
10331037

@@ -1085,44 +1089,56 @@
10851089
// @section scara
10861090

10871091
/**
1088-
* MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013.
1092+
* SCARA kinematics
1093+
*
1094+
* - Positive angles rotate counterclockwise when looking down from above.
1095+
* - Theta is the shoulder angle. 0 degrees aligns to Cartesian positive X.
1096+
* - Psi is the elbow angle. 0° is straight, ±180° is completely folded (right-handed positive, left-handed negative).
1097+
*
1098+
* The Morgan SCARA was developed by QHARLEY in South Africa in 2012-2013.
10891099
* Implemented and slightly reworked by JCERNY in June, 2014.
10901100
*
10911101
* Mostly Printed SCARA is an open source design by Tyler Williams. See:
10921102
* https://www.thingiverse.com/thing:2487048
10931103
* https://www.thingiverse.com/thing:1241491
10941104
*/
1095-
//#define MORGAN_SCARA
1096-
//#define MP_SCARA
1097-
#if ANY(MORGAN_SCARA, MP_SCARA)
1105+
1106+
//#define SCARA
1107+
#if ENABLED(SCARA)
10981108
// If movement is choppy try lowering this value
10991109
#define DEFAULT_SEGMENTS_PER_SECOND 200
11001110

11011111
// Length of inner and outer support arms. Measure arm lengths precisely.
1102-
#define SCARA_LINKAGE_1 150 // (mm)
1103-
#define SCARA_LINKAGE_2 150 // (mm)
1112+
#define SCARA_LINKAGE_1 135 // (mm)
1113+
#define SCARA_LINKAGE_2 135 // (mm)
11041114

1105-
// SCARA tower offset (position of Tower relative to bed zero position)
1115+
// SCARA tower offset (position of shoulder axis relative to bed zero position)
11061116
// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
1107-
#define SCARA_OFFSET_X 100 // (mm)
1108-
#define SCARA_OFFSET_Y -56 // (mm)
1117+
#define SCARA_OFFSET_X 0 // (mm)
1118+
#define SCARA_OFFSET_Y -150 // (mm)
11091119

1110-
#if ENABLED(MORGAN_SCARA)
1120+
// Radius of unreachable area near shoulder axis
1121+
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
11111122

1112-
//#define DEBUG_SCARA_KINEMATICS
1113-
#define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly
1123+
// Direction of elbow bend. 1 = right-handed (counterclockwise), -1 = left-handed (clockwise)
1124+
#define SCARA_ELBOW_DIR 1
11141125

1115-
// Radius around the center where the arm cannot reach
1116-
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
1126+
// This defines how shoulder movement affects the distal arm angle. Common values:
1127+
// 0.0 if distal arm retains its angle relative to proximal arm (e.g. if elbow motor rides on proximal arm)
1128+
// 1.0 if distal arm retains its angle relative to cartesian X axis (e.g. Morgan and MPSCARA)
1129+
// A two-stage reduction with an intermediate pulley on the shoulder axis has crosstalk =
1130+
// intermediate_pulley_teeth/elbow_pulley_teeth (first reduction stage does not affect crosstalk)
1131+
#define SCARA_CROSSTALK_FACTOR (40.0/60.0)
11171132

1118-
#elif ENABLED(MP_SCARA)
1133+
// Shoulder and elbow angles when in home position. If left undefined, cartesian home is used and
1134+
// angles are calculated by inverse kinematics (note: M665 home offsets are still angles)
1135+
#define SCARA_HOME_THETA -40
1136+
#define SCARA_HOME_PSI 160
11191137

1120-
#define SCARA_OFFSET_THETA1 12 // degrees
1121-
#define SCARA_OFFSET_THETA2 131 // degrees
1138+
// Enable M360-M364 to calibrate SCARA angles
1139+
//#define SCARA_CALIBRATION
11221140

1123-
#endif
1124-
1125-
#endif
1141+
#endif // SCARA
11261142

11271143
// @section tpara
11281144

config/examples/3DMatik/XL/Configuration.h

Lines changed: 38 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1015,7 +1015,9 @@
10151015

10161016
// @section polargraph
10171017

1018-
// Enable for Polargraph Kinematics
1018+
/**
1019+
* Polargraph Kinematics
1020+
*/
10191021
//#define POLARGRAPH
10201022
#if ENABLED(POLARGRAPH)
10211023
#define POLARGRAPH_MAX_BELT_LEN 1035.0 // (mm) Belt length at full extension. Override with M665 H.
@@ -1025,7 +1027,9 @@
10251027

10261028
// @section delta
10271029

1028-
// Enable for DELTA kinematics and configure below
1030+
/**
1031+
* DELTA kinematics
1032+
*/
10291033
//#define DELTA
10301034
#if ENABLED(DELTA)
10311035

@@ -1083,44 +1087,56 @@
10831087
// @section scara
10841088

10851089
/**
1086-
* MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013.
1090+
* SCARA kinematics
1091+
*
1092+
* - Positive angles rotate counterclockwise when looking down from above.
1093+
* - Theta is the shoulder angle. 0 degrees aligns to Cartesian positive X.
1094+
* - Psi is the elbow angle. 0° is straight, ±180° is completely folded (right-handed positive, left-handed negative).
1095+
*
1096+
* The Morgan SCARA was developed by QHARLEY in South Africa in 2012-2013.
10871097
* Implemented and slightly reworked by JCERNY in June, 2014.
10881098
*
10891099
* Mostly Printed SCARA is an open source design by Tyler Williams. See:
10901100
* https://www.thingiverse.com/thing:2487048
10911101
* https://www.thingiverse.com/thing:1241491
10921102
*/
1093-
//#define MORGAN_SCARA
1094-
//#define MP_SCARA
1095-
#if ANY(MORGAN_SCARA, MP_SCARA)
1103+
1104+
//#define SCARA
1105+
#if ENABLED(SCARA)
10961106
// If movement is choppy try lowering this value
10971107
#define DEFAULT_SEGMENTS_PER_SECOND 200
10981108

10991109
// Length of inner and outer support arms. Measure arm lengths precisely.
1100-
#define SCARA_LINKAGE_1 150 // (mm)
1101-
#define SCARA_LINKAGE_2 150 // (mm)
1110+
#define SCARA_LINKAGE_1 135 // (mm)
1111+
#define SCARA_LINKAGE_2 135 // (mm)
11021112

1103-
// SCARA tower offset (position of Tower relative to bed zero position)
1113+
// SCARA tower offset (position of shoulder axis relative to bed zero position)
11041114
// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
1105-
#define SCARA_OFFSET_X 100 // (mm)
1106-
#define SCARA_OFFSET_Y -56 // (mm)
1115+
#define SCARA_OFFSET_X 0 // (mm)
1116+
#define SCARA_OFFSET_Y -150 // (mm)
11071117

1108-
#if ENABLED(MORGAN_SCARA)
1118+
// Radius of unreachable area near shoulder axis
1119+
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
11091120

1110-
//#define DEBUG_SCARA_KINEMATICS
1111-
#define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly
1121+
// Direction of elbow bend. 1 = right-handed (counterclockwise), -1 = left-handed (clockwise)
1122+
#define SCARA_ELBOW_DIR 1
11121123

1113-
// Radius around the center where the arm cannot reach
1114-
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
1124+
// This defines how shoulder movement affects the distal arm angle. Common values:
1125+
// 0.0 if distal arm retains its angle relative to proximal arm (e.g. if elbow motor rides on proximal arm)
1126+
// 1.0 if distal arm retains its angle relative to cartesian X axis (e.g. Morgan and MPSCARA)
1127+
// A two-stage reduction with an intermediate pulley on the shoulder axis has crosstalk =
1128+
// intermediate_pulley_teeth/elbow_pulley_teeth (first reduction stage does not affect crosstalk)
1129+
#define SCARA_CROSSTALK_FACTOR (40.0/60.0)
11151130

1116-
#elif ENABLED(MP_SCARA)
1131+
// Shoulder and elbow angles when in home position. If left undefined, cartesian home is used and
1132+
// angles are calculated by inverse kinematics (note: M665 home offsets are still angles)
1133+
#define SCARA_HOME_THETA -40
1134+
#define SCARA_HOME_PSI 160
11171135

1118-
#define SCARA_OFFSET_THETA1 12 // degrees
1119-
#define SCARA_OFFSET_THETA2 131 // degrees
1136+
// Enable M360-M364 to calibrate SCARA angles
1137+
//#define SCARA_CALIBRATION
11201138

1121-
#endif
1122-
1123-
#endif
1139+
#endif // SCARA
11241140

11251141
// @section tpara
11261142

config/examples/ADIMLab/Gantry v1/Configuration.h

Lines changed: 38 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1015,7 +1015,9 @@
10151015

10161016
// @section polargraph
10171017

1018-
// Enable for Polargraph Kinematics
1018+
/**
1019+
* Polargraph Kinematics
1020+
*/
10191021
//#define POLARGRAPH
10201022
#if ENABLED(POLARGRAPH)
10211023
#define POLARGRAPH_MAX_BELT_LEN 1035.0 // (mm) Belt length at full extension. Override with M665 H.
@@ -1025,7 +1027,9 @@
10251027

10261028
// @section delta
10271029

1028-
// Enable for DELTA kinematics and configure below
1030+
/**
1031+
* DELTA kinematics
1032+
*/
10291033
//#define DELTA
10301034
#if ENABLED(DELTA)
10311035

@@ -1083,44 +1087,56 @@
10831087
// @section scara
10841088

10851089
/**
1086-
* MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013.
1090+
* SCARA kinematics
1091+
*
1092+
* - Positive angles rotate counterclockwise when looking down from above.
1093+
* - Theta is the shoulder angle. 0 degrees aligns to Cartesian positive X.
1094+
* - Psi is the elbow angle. 0° is straight, ±180° is completely folded (right-handed positive, left-handed negative).
1095+
*
1096+
* The Morgan SCARA was developed by QHARLEY in South Africa in 2012-2013.
10871097
* Implemented and slightly reworked by JCERNY in June, 2014.
10881098
*
10891099
* Mostly Printed SCARA is an open source design by Tyler Williams. See:
10901100
* https://www.thingiverse.com/thing:2487048
10911101
* https://www.thingiverse.com/thing:1241491
10921102
*/
1093-
//#define MORGAN_SCARA
1094-
//#define MP_SCARA
1095-
#if ANY(MORGAN_SCARA, MP_SCARA)
1103+
1104+
//#define SCARA
1105+
#if ENABLED(SCARA)
10961106
// If movement is choppy try lowering this value
10971107
#define DEFAULT_SEGMENTS_PER_SECOND 200
10981108

10991109
// Length of inner and outer support arms. Measure arm lengths precisely.
1100-
#define SCARA_LINKAGE_1 150 // (mm)
1101-
#define SCARA_LINKAGE_2 150 // (mm)
1110+
#define SCARA_LINKAGE_1 135 // (mm)
1111+
#define SCARA_LINKAGE_2 135 // (mm)
11021112

1103-
// SCARA tower offset (position of Tower relative to bed zero position)
1113+
// SCARA tower offset (position of shoulder axis relative to bed zero position)
11041114
// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
1105-
#define SCARA_OFFSET_X 100 // (mm)
1106-
#define SCARA_OFFSET_Y -56 // (mm)
1115+
#define SCARA_OFFSET_X 0 // (mm)
1116+
#define SCARA_OFFSET_Y -150 // (mm)
11071117

1108-
#if ENABLED(MORGAN_SCARA)
1118+
// Radius of unreachable area near shoulder axis
1119+
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
11091120

1110-
//#define DEBUG_SCARA_KINEMATICS
1111-
#define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly
1121+
// Direction of elbow bend. 1 = right-handed (counterclockwise), -1 = left-handed (clockwise)
1122+
#define SCARA_ELBOW_DIR 1
11121123

1113-
// Radius around the center where the arm cannot reach
1114-
#define MIDDLE_DEAD_ZONE_R 0 // (mm)
1124+
// This defines how shoulder movement affects the distal arm angle. Common values:
1125+
// 0.0 if distal arm retains its angle relative to proximal arm (e.g. if elbow motor rides on proximal arm)
1126+
// 1.0 if distal arm retains its angle relative to cartesian X axis (e.g. Morgan and MPSCARA)
1127+
// A two-stage reduction with an intermediate pulley on the shoulder axis has crosstalk =
1128+
// intermediate_pulley_teeth/elbow_pulley_teeth (first reduction stage does not affect crosstalk)
1129+
#define SCARA_CROSSTALK_FACTOR (40.0/60.0)
11151130

1116-
#elif ENABLED(MP_SCARA)
1131+
// Shoulder and elbow angles when in home position. If left undefined, cartesian home is used and
1132+
// angles are calculated by inverse kinematics (note: M665 home offsets are still angles)
1133+
#define SCARA_HOME_THETA -40
1134+
#define SCARA_HOME_PSI 160
11171135

1118-
#define SCARA_OFFSET_THETA1 12 // degrees
1119-
#define SCARA_OFFSET_THETA2 131 // degrees
1136+
// Enable M360-M364 to calibrate SCARA angles
1137+
//#define SCARA_CALIBRATION
11201138

1121-
#endif
1122-
1123-
#endif
1139+
#endif // SCARA
11241140

11251141
// @section tpara
11261142

0 commit comments

Comments
 (0)