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