1 #include "RotatableDeltaSolution.h"
3 #include "ConfigValue.h"
4 #include "ConfigCache.h"
5 #include "libs/Kernel.h"
6 #include "libs/nuts_bolts.h"
7 #include "libs/Config.h"
8 #include "libs/utils.h"
9 #include "StreamOutputPool.h"
12 #define delta_e_checksum CHECKSUM("delta_e_checksum")
13 #define delta_f_checksum CHECKSUM("delta_f_checksum")
14 #define delta_re_checksum CHECKSUM("delta_re_checksum")
15 #define delta_rf_checksum CHECKSUM("delta_rf_checksum")
16 #define delta_z_offset_checksum CHECKSUM("delta_z_offset_checksum")
18 #define delta_ee_offs_checksum CHECKSUM("delta_ee_offs_checksum")
19 #define tool_offset_checksum CHECKSUM("tool_offset_checksum")
21 #ifndef alpha_steps_per_mm_checksum
22 #define alpha_steps_per_mm_checksum CHECKSUM("alpha_steps_per_mm_checksum");
25 #ifndef beta_steps_per_mm_checksum
26 #define beta_steps_per_mm_checksum CHECKSUM("beta_steps_per_mm_checksum");
29 #ifndef gamma_steps_per_mm_checksum
30 #define gamma_steps_per_mm_checksum CHECKSUM("gamma_steps_per_mm_checksum");
33 const static float pi
= 3.14159265358979323846; // PI
34 const static float two_pi
= 2 * pi
;
35 const static float sin120
= 0.86602540378443864676372317075294; //sqrt3/2.0
36 const static float cos120
= -0.5;
37 const static float tan60
= 1.7320508075688772935274463415059; //sqrt3;
38 const static float sin30
= 0.5;
39 const static float tan30
= 0.57735026918962576450914878050196; //1/sqrt3
41 RotatableDeltaSolution::RotatableDeltaSolution(Config
* config
)
43 // End effector length
44 delta_e
= config
->value(delta_e_checksum
)->by_default(131.636F
)->as_number();
47 delta_f
= config
->value(delta_f_checksum
)->by_default(190.526F
)->as_number();
50 delta_re
= config
->value(delta_re_checksum
)->by_default(270.000F
)->as_number();
53 delta_rf
= config
->value(delta_rf_checksum
)->by_default(90.000F
)->as_number();
55 // Distance from delta 8mm rod/pulley to table/bed,
56 // NOTE: For OpenPnP, set the zero to be about 25mm above the bed..
57 delta_z_offset
= config
->value(delta_z_offset_checksum
)->by_default(290.700F
)->as_number();
59 // Ball joint plane to bottom of end effector surface
60 delta_ee_offs
= config
->value(delta_ee_offs_checksum
)->by_default(15.000F
)->as_number();
62 // Distance between end effector ball joint plane and tip of tool (PnP)
63 tool_offset
= config
->value(tool_offset_checksum
)->by_default(30.500F
)->as_number();
69 // helper functions, calculates angle theta1 (for YZ-pane)
70 int RotatableDeltaSolution::delta_calcAngleYZ(float x0
, float y0
, float z0
, float &theta
)
72 float y1
= -0.5F
* tan30
* delta_f
; // f/2 * tan 30
73 y0
-= 0.5F
* tan30
* delta_e
; // shift center to edge
75 float a
= (x0
*x0
+ y0
*y0
+ z0
*z0
+ delta_rf
*delta_rf
- delta_re
*delta_re
- y1
*y1
) / (2.0F
*z0
);
78 float d
= -(a
+b
*y1
)*(a
+b
*y1
) + delta_rf
*(b
*b
*delta_rf
+delta_rf
); // discriminant
79 if (d
< 0.0F
) return -1; // non-existing point
81 float yj
= (y1
- a
*b
- sqrtf(d
))/(b
*b
+ 1.0F
); // choosing outer point
84 theta
= 180.0F
*atanf(-zj
/(y1
- yj
))/pi
+ ((yj
>y1
)?180.0F
:0.0F
);
88 // forward kinematics: (theta1, theta2, theta3) -> (x0, y0, z0)
89 // returned status: 0=OK, -1=non-existing position
90 int RotatableDeltaSolution::delta_calcForward(float theta1
, float theta2
, float theta3
, float &x0
, float &y0
, float &z0
)
92 float t
= (delta_f
-delta_e
)*tan30
/2.0F
;
93 float degrees_to_radians
= pi
/180.0F
;
95 theta1
*= degrees_to_radians
;
96 theta2
*= degrees_to_radians
;
97 theta3
*= degrees_to_radians
;
99 float y1
= -(t
+ delta_rf
*cosf(theta1
));
100 float z1
= -delta_rf
*sinf(theta1
);
102 float y2
= (t
+ delta_rf
*cosf(theta2
))*sin30
;
104 float z2
= -delta_rf
*sinf(theta2
);
106 float y3
= (t
+ delta_rf
*cosf(theta3
))*sin30
;
107 float x3
= -y3
*tan60
;
108 float z3
= -delta_rf
*sinf(theta3
);
110 float dnm
= (y2
-y1
)*x3
-(y3
-y1
)*x2
;
112 float w1
= y1
*y1
+ z1
*z1
;
113 float w2
= x2
*x2
+ y2
*y2
+ z2
*z2
;
114 float w3
= x3
*x3
+ y3
*y3
+ z3
*z3
;
116 // x = (a1*z + b1)/dnm
117 float a1
= (z2
-z1
)*(y3
-y1
)-(z3
-z1
)*(y2
-y1
);
118 float b1
= -((w2
-w1
)*(y3
-y1
)-(w3
-w1
)*(y2
-y1
))/2.0F
;
120 // y = (a2*z + b2)/dnm;
121 float a2
= -(z2
-z1
)*x3
+(z3
-z1
)*x2
;
122 float b2
= ((w2
-w1
)*x3
- (w3
-w1
)*x2
)/2.0F
;
124 // a*z^2 + b*z + c = 0
125 float a
= a1
*a1
+ a2
*a2
+ dnm
*dnm
;
126 float b
= 2.0F
*(a1
*b1
+ a2
*(b2
-y1
*dnm
) - z1
*dnm
*dnm
);
127 float c
= (b2
-y1
*dnm
)*(b2
-y1
*dnm
) + b1
*b1
+ dnm
*dnm
*(z1
*z1
- delta_re
*delta_re
);
130 float d
= b
*b
- (float)4.0F
*a
*c
;
131 if (d
< 0.0F
) return -1; // non-existing point
133 z0
= -(float)0.5F
*(b
+sqrtf(d
))/a
;
134 x0
= (a1
*z0
+ b1
)/dnm
;
135 y0
= (a2
*z0
+ b2
)/dnm
;
137 z0
+= z_calc_offset
; //nj
142 void RotatableDeltaSolution::init() {
144 //these are calculated here and not in the config() as these variables can be fine tuned by the user.
145 z_calc_offset
= (delta_z_offset
- tool_offset
- delta_ee_offs
)*-1.0F
;
147 // This is calculated from the Z_HOME_ANGLE angles after applying forward kinematics, and adding the Z calc offset to it.
148 z_home_offs
= (((delta_z_offset
- tool_offset
- delta_ee_offs
) - 182.002F
) - 0.5F
);
152 void RotatableDeltaSolution::cartesian_to_actuator( float cartesian_mm
[], float actuator_mm
[] )
154 //We need to translate the Cartesian coordinates in mm to the actuator position required in mm so the stepper motor functions
155 float alpha_theta
= 0.0F
;
156 float beta_theta
= 0.0F
;
157 float gamma_theta
= 0.0F
;
159 //Code from Trossen Robotics tutorial, note we put the X axis at the back and not the front of the robot.
161 float x0
= cartesian_mm
[X_AXIS
];
162 float y0
= cartesian_mm
[Y_AXIS
];
163 float z_with_offset
= cartesian_mm
[Z_AXIS
] + z_calc_offset
; //The delta calculation below places zero at the top. Subtract the Z offset to make zero at the bottom.
165 int status
= delta_calcAngleYZ(x0
, y0
, z_with_offset
, alpha_theta
);
166 if (status
== 0) status
= delta_calcAngleYZ(x0
*cos120
+ y0
*sin120
, y0
*cos120
-x0
*sin120
, z_with_offset
, beta_theta
); // rotate co-ordinates to +120 deg
167 if (status
== 0) status
= delta_calcAngleYZ(x0
*cos120
- y0
*sin120
, y0
*cos120
+x0
*sin120
, z_with_offset
, gamma_theta
); // rotate co-ordinates to -120 deg
169 if (status
== -1) //something went wrong,
171 //force to actuator FPD home position as we know this is a valid position
172 actuator_mm
[ALPHA_STEPPER
] = 0;
173 actuator_mm
[BETA_STEPPER
] = 0;
174 actuator_mm
[GAMMA_STEPPER
] = 0;
176 //DEBUG CODE, uncomment the following to help determine what may be happening if you are trying to adapt this to your own different roational delta.
177 // THEKERNEL->streams->printf("ERROR: Delta calculation fail! Unable to move to:\n");
178 // THEKERNEL->streams->printf(" x= %f\n",cartesian_mm[X_AXIS]);
179 // THEKERNEL->streams->printf(" y= %f\n",cartesian_mm[Y_AXIS]);
180 // THEKERNEL->streams->printf(" z= %f\n",cartesian_mm[Z_AXIS]);
181 // THEKERNEL->streams->printf(" CalcZ= %f\n",z_calc_offset);
182 // THEKERNEL->streams->printf(" Offz= %f\n",z_with_offset);
186 actuator_mm
[ALPHA_STEPPER
] = alpha_theta
;
187 actuator_mm
[BETA_STEPPER
] = beta_theta
;
188 actuator_mm
[GAMMA_STEPPER
] = gamma_theta
;
190 // THEKERNEL->streams->printf("cartesian x= %f\n\r",cartesian_mm[X_AXIS]);
191 // THEKERNEL->streams->printf(" y= %f\n\r",cartesian_mm[Y_AXIS]);
192 // THEKERNEL->streams->printf(" z= %f\n\r",cartesian_mm[Z_AXIS]);
193 // THEKERNEL->streams->printf(" Offz= %f\n\r",z_with_offset);
194 // THEKERNEL->streams->printf(" delta x= %f\n\r",delta[X_AXIS]);
195 // THEKERNEL->streams->printf(" y= %f\n\r",delta[Y_AXIS]);
196 // THEKERNEL->streams->printf(" z= %f\n\r",delta[Z_AXIS]);
201 void RotatableDeltaSolution::actuator_to_cartesian( float actuator_mm
[], float cartesian_mm
[] )
203 //Use forward kinematics
204 delta_calcForward(actuator_mm
[ALPHA_STEPPER
], actuator_mm
[BETA_STEPPER
], actuator_mm
[GAMMA_STEPPER
], cartesian_mm
[X_AXIS
], cartesian_mm
[Y_AXIS
], cartesian_mm
[Z_AXIS
]);
207 bool RotatableDeltaSolution::set_optional(const arm_options_t
& options
) {
209 for(auto &i
: options
) {
211 case 'A': delta_e
= i
.second
; break;
212 case 'B': delta_f
= i
.second
; break;
213 case 'C': delta_re
= i
.second
; break;
214 case 'D': delta_rf
= i
.second
; break;
215 case 'E': delta_z_offset
= i
.second
; break;
216 case 'F': delta_ee_offs
= i
.second
; break;
217 case 'H': tool_offset
= i
.second
; break;
224 bool RotatableDeltaSolution::get_optional(arm_options_t
& options
) {
226 // don't report these if none of them are set
227 if(this->delta_e
!= 0.0F
|| this->delta_f
!= 0.0F
|| this->delta_re
!= 0.0F
||
228 this->delta_rf
!= 0.0F
|| this->delta_z_offset
!= 0.0F
|| this->delta_ee_offs
!= 0.0F
||
229 this->tool_offset
!= 0.0F
) {
231 options
['A'] = this->delta_e
;
232 options
['B'] = this->delta_f
;
233 options
['C'] = this->delta_re
;
234 options
['D'] = this->delta_rf
;
235 options
['E'] = this->delta_z_offset
;
236 options
['F'] = this->delta_ee_offs
;
237 options
['H'] = this->tool_offset
;