modified: src/modules/robot/arm_solutions/RotatableDeltaSolution.cpp
[clinton/Smoothieware.git] / src / modules / robot / arm_solutions / RotatableDeltaSolution.cpp
1 #include "RotatableDeltaSolution.h"
2 #include "checksumm.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"
10 #include <fastmath.h>
11
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")
17
18 #define delta_ee_offs_checksum CHECKSUM("delta_ee_offs_checksum")
19 #define tool_offset_checksum CHECKSUM("tool_offset_checksum")
20
21 #define z_home_angle_checksum CHECKSUM("z_home_angle_checksum")
22
23 #define delta_printable_radius_checksum CHECKSUM("delta_printable_radius_checksum")
24
25 #ifndef alpha_steps_per_mm_checksum
26 #define alpha_steps_per_mm_checksum CHECKSUM("alpha_steps_per_mm_checksum");
27 #endif
28
29 #ifndef beta_steps_per_mm_checksum
30 #define beta_steps_per_mm_checksum CHECKSUM("beta_steps_per_mm_checksum");
31 #endif
32
33 #ifndef gamma_steps_per_mm_checksum
34 #define gamma_steps_per_mm_checksum CHECKSUM("gamma_steps_per_mm_checksum");
35 #endif
36
37 const static float pi = 3.14159265358979323846; // PI
38 const static float two_pi = 2 * pi;
39 const static float sin120 = 0.86602540378443864676372317075294; //sqrt3/2.0
40 const static float cos120 = -0.5;
41 const static float tan60 = 1.7320508075688772935274463415059; //sqrt3;
42 const static float sin30 = 0.5;
43 const static float tan30 = 0.57735026918962576450914878050196; //1/sqrt3
44
45 RotatableDeltaSolution::RotatableDeltaSolution(Config* config)
46 {
47 // End effector length
48 delta_e = config->value((unsigned int)delta_e_checksum)->by_default(131.636F)->as_number();
49
50 // Base length
51 delta_f = config->value((unsigned int)delta_f_checksum)->by_default(190.526F)->as_number();
52
53 // Carbon rod length
54 delta_re = config->value((unsigned int)delta_re_checksum)->by_default(270.000F)->as_number();
55
56 // Servo horn length
57 delta_rf = config->value((unsigned int)delta_rf_checksum)->by_default(90.000F)->as_number();
58
59 // Distance from delta 8mm rod/pulley to table/bed,
60 // NOTE: For OpenPnP, set the zero to be about 25mm above the bed..
61 delta_z_offset = config->value((unsigned int)delta_z_offset_checksum)->by_default(290.700F)->as_number();
62
63 // Ball joint plane to bottom of end effector surface
64 delta_ee_offs = config->value((unsigned int)delta_ee_offs_checksum)->by_default(15.000F)->as_number();
65
66 // Distance between end effector ball joint plane and tip of tool (PnP)
67 tool_offset = config->value((unsigned int)tool_offset_checksum)->by_default(30.500F)->as_number();
68
69 // This is the angle where the arms hit the endstop sensor
70 z_home_angle = config->value((unsigned int)z_home_angle_checksum)->by_default(-60.000F)->as_number();
71
72 // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers).
73 delta_printable_radius = config->value((unsigned int)delta_printable_radius_checksum)->by_default(150.0F)->as_number();
74
75 init();
76 }
77
78 // inverse kinematics
79 // helper functions, calculates angle theta1 (for YZ-pane)
80 int RotatableDeltaSolution::delta_calcAngleYZ(float x0, float y0, float z0, float &theta)
81 {
82 float y1 = -0.5F * tan30 * delta_f; // f/2 * tan 30
83 y0 -= 0.5F * tan30 * delta_e; // shift center to edge
84 // z = a + b*y
85 float a = (x0*x0 + y0*y0 + z0*z0 + delta_rf*delta_rf - delta_re*delta_re - y1*y1) / (2.0F*z0);
86 float b = (y1-y0)/z0;
87
88 float d = -(a+b*y1)*(a+b*y1) + delta_rf*(b*b*delta_rf+delta_rf); // discriminant
89 if (d < 0.0F) return -1; // non-existing point
90
91 float yj = (y1 - a*b - sqrtf(d))/(b*b + 1.0F); // choosing outer point
92 float zj = a + b*yj;
93
94 theta = 180.0F*atanf(-zj/(y1 - yj))/pi + ((yj>y1)?180.0F:0.0F);
95 return 0;
96 }
97
98 // forward kinematics: (theta1, theta2, theta3) -> (x0, y0, z0)
99 // returned status: 0=OK, -1=non-existing position
100 int RotatableDeltaSolution::delta_calcForward(float theta1, float theta2, float theta3, float &x0, float &y0, float &z0)
101 {
102 float t = (delta_f-delta_e)*tan30/2.0F;
103 float degrees_to_radians = pi/180.0F;
104
105 theta1 *= degrees_to_radians;
106 theta2 *= degrees_to_radians;
107 theta3 *= degrees_to_radians;
108
109 float y1 = -(t + delta_rf*cosf(theta1));
110 float z1 = -delta_rf*sinf(theta1);
111
112 float y2 = (t + delta_rf*cosf(theta2))*sin30;
113 float x2 = y2*tan60;
114 float z2 = -delta_rf*sinf(theta2);
115
116 float y3 = (t + delta_rf*cosf(theta3))*sin30;
117 float x3 = -y3*tan60;
118 float z3 = -delta_rf*sinf(theta3);
119
120 float dnm = (y2-y1)*x3-(y3-y1)*x2;
121
122 float w1 = y1*y1 + z1*z1;
123 float w2 = x2*x2 + y2*y2 + z2*z2;
124 float w3 = x3*x3 + y3*y3 + z3*z3;
125
126 // x = (a1*z + b1)/dnm
127 float a1 = (z2-z1)*(y3-y1)-(z3-z1)*(y2-y1);
128 float b1 = -((w2-w1)*(y3-y1)-(w3-w1)*(y2-y1))/2.0F;
129
130 // y = (a2*z + b2)/dnm;
131 float a2 = -(z2-z1)*x3+(z3-z1)*x2;
132 float b2 = ((w2-w1)*x3 - (w3-w1)*x2)/2.0F;
133
134 // a*z^2 + b*z + c = 0
135 float a = a1*a1 + a2*a2 + dnm*dnm;
136 float b = 2.0F*(a1*b1 + a2*(b2-y1*dnm) - z1*dnm*dnm);
137 float c = (b2-y1*dnm)*(b2-y1*dnm) + b1*b1 + dnm*dnm*(z1*z1 - delta_re*delta_re);
138
139 // discriminant
140 float d = b*b - (float)4.0F*a*c;
141 if (d < 0.0F) return -1; // non-existing point
142
143 z0 = -(float)0.5F*(b+sqrtf(d))/a;
144 x0 = (a1*z0 + b1)/dnm;
145 y0 = (a2*z0 + b2)/dnm;
146
147 z0 += z_calc_offset; //nj
148 return 0;
149 }
150
151
152 void RotatableDeltaSolution::init() {
153
154 z_calc_offset = (delta_z_offset - tool_offset - delta_ee_offs)*-1.0F;
155
156 // This is calculated from the Z_HOME_ANGLE angles specified in the config (file), after applying forward
157 // kinematics, and adding the Z calc offset to it.
158 z_home_offs = (((delta_z_offset - tool_offset - delta_ee_offs) - 182.002F) - 0.5F);
159
160 }
161
162 void RotatableDeltaSolution::cartesian_to_actuator( float cartesian_mm[], float actuator_mm[] )
163 {
164 //We need to translate the Cartesian coordinates in mm to the actuator position required in mm so the stepper motor functions
165 float alpha_theta = 0.0F;
166 float beta_theta = 0.0F;
167 float gamma_theta = 0.0F;
168
169 //Code from Trossen Robotics tutorial, note we put the X axis at the back and not the front of the robot.
170
171 float x0 = cartesian_mm[X_AXIS];
172 float y0 = cartesian_mm[Y_AXIS];
173 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.
174
175 int status = delta_calcAngleYZ(x0, y0, z_with_offset, alpha_theta);
176 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
177 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
178
179 if (status == -1) //something went wrong
180 {
181 //Do nothing so the actuator_mm is unchanged by this routine.
182 // as we have no idea what it should be
183 //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.
184 // THEKERNEL->streams->printf("ERROR: Delta calculation fail! Unable to move to:\n");
185 // THEKERNEL->streams->printf(" x= %f\n",cartesian_mm[X_AXIS]);
186 // THEKERNEL->streams->printf(" y= %f\n",cartesian_mm[Y_AXIS]);
187 // THEKERNEL->streams->printf(" z= %f\n",cartesian_mm[Z_AXIS]);
188 // THEKERNEL->streams->printf(" CalcZ= %f\n",z_calc_offset);
189 // THEKERNEL->streams->printf(" Offz= %f\n",z_with_offset);
190 }
191 else
192 {
193 actuator_mm[ALPHA_STEPPER] = alpha_theta;
194 actuator_mm[BETA_STEPPER ] = beta_theta;
195 actuator_mm[GAMMA_STEPPER] = gamma_theta;
196
197 // THEKERNEL->streams->printf("cartesian x= %f\n\r",cartesian_mm[X_AXIS]);
198 // THEKERNEL->streams->printf(" y= %f\n\r",cartesian_mm[Y_AXIS]);
199 // THEKERNEL->streams->printf(" z= %f\n\r",cartesian_mm[Z_AXIS]);
200 // THEKERNEL->streams->printf(" Offz= %f\n\r",z_with_offset);
201 // THEKERNEL->streams->printf(" delta x= %f\n\r",delta[X_AXIS]);
202 // THEKERNEL->streams->printf(" y= %f\n\r",delta[Y_AXIS]);
203 // THEKERNEL->streams->printf(" z= %f\n\r",delta[Z_AXIS]);
204 }
205
206 }
207
208 void RotatableDeltaSolution::actuator_to_cartesian( float actuator_mm[], float cartesian_mm[] )
209 {
210 //Use forward kinematics
211 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]);
212 }
213
214 bool RotatableDeltaSolution::set_optional(const arm_options_t& options) {
215
216 for(auto &i : options) {
217 switch(i.first) {
218 case 'A': delta_e = i.second; break;
219 case 'B': delta_f = i.second; break;
220 case 'C': delta_re = i.second; break;
221 case 'D': delta_rf = i.second; break;
222 case 'E': delta_z_offset = i.second; break;
223 case 'F': delta_ee_offs = i.second; break;
224 case 'H': tool_offset = i.second; break;
225 case 'I': z_home_angle = i.second; break;
226 case 'J': delta_printable_radius = i.second; break;
227 }
228 }
229 init();
230 return true;
231 }
232
233 bool RotatableDeltaSolution::get_optional(arm_options_t& options) {
234
235 // don't report these if none of them are set
236 if(this->delta_e != 0.0F || this->delta_f != 0.0F || this->delta_re != 0.0F ||
237 this->delta_rf != 0.0F || this->delta_z_offset != 0.0F || this->delta_ee_offs != 0.0F ||
238 this->tool_offset != 0.0F || this->z_home_angle != 0.0F || this->delta_printable_radius != 0.0F) {
239
240 options['A'] = this->delta_e;
241 options['B'] = this->delta_f;
242 options['C'] = this->delta_re;
243 options['D'] = this->delta_rf;
244 options['E'] = this->delta_z_offset;
245 options['F'] = this->delta_ee_offs;
246 options['H'] = this->tool_offset;
247 options['I'] = this->z_home_angle;
248 options['J'] = this->delta_printable_radius;
249 }
250
251 return true;
252 };
253