2009 , - ( — ). , ( ), , , - TrossenRobotics — . - . , , , . , .
-, , ( ) — . , , C.
-
- (
wiki) 1980- , US4976582 « »:
: (1) (8), . : (4) (3), , (5), .. (6, 7) (
wiki), . (16) , . , . , .
(8) .. ( end effector) (9). , , , 3D . (11), (14).
- : , , , . , , 
Geektimes .
-, . , (, , 
(x, y, z). , , , . ( «») .
, ( , , ), (, ). — .
. , : . ( — ) 
Ѳ1, 
Ѳ2 Ѳ3, 
0, — 
(x0, y0, z0).
, :
- finverse(x0, y0, z0) → (Ѳ1, Ѳ2, Ѳ3)
- fforward(Ѳ1, Ѳ2, Ѳ3) → (x0, y0, z0) .
, :
f, 
e, 
rf ( ) 
re. , . 
Z , , z- .
, 
F1J1 (. ) 
YZ, 
rf F1 ( ). 
F1, 
J1 E1 , 
E1J1 E1, 
re E1.
YZ E’1 E’1J1, 
E’1 E1 YZ. 
J1 E’1 F1, . : , — 
y, , «» . 
J1, 
Ѳ1.
YZ:
, 
E0(x0, y0, z0). ,
E1 E’1 YZ:
E1E’1=x0, , ,
, 
F1J1, , :
, , :
, z- 
J1 y-, , , y, ( ). 
J1,
: 
F1J1 YZ, 
x. 
Ѳ2 Ѳ3, -. 120° 
XY Z:
X’Y’Z’, 
Ѳ2. , 
E0 . ( ), . 
Ѳ3 , . : Ѳ YZ, .
: 
Ѳ1, 
Ѳ2 Ѳ3, 
(x0, y0, z0) E0, . , 
J1, 
J2 J3 (. ). 
J1E1, 
J2E2 J3E3 J1, 
J2 J3 , 
re.
: 
J1, 
J2, 
J3 XY Z, 
E1E0, 
E2E0 E3E0 ( ). , 
E0, :
, 
(x0, y0, z0) E0 , . , , :
(xi, yi, zi) — 
J’1, 
J’2 J’3, :
J’1, 
J’2 J’3 (x1, y1, z1), 
(x2, y2, z2) (x3, y3, z3) . , 
x1=0 ( 
J’1 YZ). :
, , , :
(, , 
y) ( 
x), 
x y z:
, 
x y, 
z, ( 
J’1), :
( , ), 
z ( , 
z!), 
x y.
- . , , 
theta1, 
theta2 theta3 .
const float e = 115.0;     
const float f = 457.3;     
const float re = 232.0;
const float rf = 112.0;
const float sqrt3 = sqrt(3.0);
const float pi = 3.141592653;    
const float sin120 = sqrt3/2.0;
const float cos120 = -0.5;
const float tan60 = sqrt3;
const float sin30 = 0.5;
const float tan30 = 1/sqrt3;
int delta_calcForward(float theta1, float theta2, float theta3, float &x0, float &y0, float &z0) {
    float t = (f-e)*tan30/2;
    float dtr = pi/(float)180.0;
    theta1 *= dtr;
    theta2 *= dtr;
    theta3 *= dtr;
    float y1 = -(t + rf*cos(theta1));
    float z1 = -rf*sin(theta1);
    float y2 = (t + rf*cos(theta2))*sin30;
    float x2 = y2*tan60;
    float z2 = -rf*sin(theta2);
    float y3 = (t + rf*cos(theta3))*sin30;
    float x3 = -y3*tan60;
    float z3 = -rf*sin(theta3);
    float dnm = (y2-y1)*x3-(y3-y1)*x2;
    float w1 = y1*y1 + z1*z1;
    float w2 = x2*x2 + y2*y2 + z2*z2;
    float w3 = x3*x3 + y3*y3 + z3*z3;
    
    float a1 = (z2-z1)*(y3-y1)-(z3-z1)*(y2-y1);
    float b1 = -((w2-w1)*(y3-y1)-(w3-w1)*(y2-y1))/2.0;
    
    float a2 = -(z2-z1)*x3+(z3-z1)*x2;
    float b2 = ((w2-w1)*x3 - (w3-w1)*x2)/2.0;
    
    float a = a1*a1 + a2*a2 + dnm*dnm;
    float b = 2*(a1*b1 + a2*(b2-y1*dnm) - z1*dnm*dnm);
    float c = (b2-y1*dnm)*(b2-y1*dnm) + b1*b1 + dnm*dnm*(z1*z1 - re*re);
    
    float d = b*b - (float)4.0*a*c;
    if (d < 0) return -1; 
    z0 = -(float)0.5*(b+sqrt(d))/a;
    x0 = (a1*z0 + b1)/dnm;
    y0 = (a2*z0 + b2)/dnm;
    return 0;
}
int delta_calcAngleYZ(float x0, float y0, float z0, float &theta) {
    float y1 = -0.5 * 0.57735 * f; 
    y0 -= 0.5 * 0.57735 * e;       
    
    float a = (x0*x0 + y0*y0 + z0*z0 +rf*rf - re*re - y1*y1)/(2*z0);
    float b = (y1-y0)/z0;
    
    float d = -(a+b*y1)*(a+b*y1)+rf*(b*b*rf+rf);
    if (d < 0) return -1; 
    float yj = (y1 - a*b - sqrt(d))/(b*b + 1); 
    float zj = a + b*yj;
    theta = 180.0*atan(-zj/(y1 - yj))/pi + ((yj>y1)?180.0:0.0);
    return 0;
}
int delta_calcInverse(float x0, float y0, float z0, float &theta1, float &theta2, float &theta3) {
    theta1 = theta2 = theta3 = 0;
    int status = delta_calcAngleYZ(x0, y0, z0, theta1);
    if (status == 0) status = delta_calcAngleYZ(x0*cos120 + y0*sin120, y0*cos120-x0*sin120, z0, theta2);  
    if (status == 0) status = delta_calcAngleYZ(x0*cos120 - y0*sin120, y0*cos120+x0*sin120, z0, theta3);  
    return status;
}
- . Paul Zsombor-Murray «
Descriptive Geometric Kinematic Analysis of Clavel’s «Delta» Robot». , , , .
, . , - -.