static int scaraKinematicsInverse(const EmcPose * world, double * joint, const KINEMATICS_INVERSE_FLAGS * iflags, KINEMATICS_FORWARD_FLAGS * fflags) { double a3; double q0, q1; double xt, yt, xt1, yt1, rsq, cc; double x, y, z, c; x = world->tran.x; y = world->tran.y; z = world->tran.z; c = world->c; /* convert degrees to radians */ a3 = c * ( PM_PI / 180 ); /* center of end effector (correct for D6) */ xt = x - D6*cos(a3); yt = y - D6*sin(a3); xt1 = xt; yt1 = yt; /* horizontal distance (squared) from end effector centerline to main column centerline */ rsq = xt*xt + yt*yt; /* joint 1 angle needed to make arm length match sqrt(rsq) */ cc = (rsq - D2*D2 - D4*D4) / (2*D2*D4); if(cc < -1) cc = -1; if(cc > 1) cc = 1; q1 = acos(cc); if (*iflags) q1 = -q1; /* angle to end effector */ q0 = atan2(yt, xt); /* end effector coords in inner arm coord system */ xt = D2 + D4*cos(q1); yt = D4*sin(q1); /* inner arm angle on both geometry of scara */ /* in front j0 column area and in behind jo column area */ /* with DX bit pin you can change *fflags */ if(DX==1){if((xt1<0) && (yt1<0)){q0 = q0 - atan2(yt, xt) + 2*M_PI;} else{q0 = q0 - atan2(yt, xt);}} else{if((xt1<0) && (yt1>=0)){q0 = q0 - atan2(yt, xt) - 2*M_PI;} else{q0 = q0 - atan2(yt, xt);}} /* q0 and q1 are still in radians. convert them to degrees */ q0 = q0 * (180 / PM_PI); q1 = q1 * (180 / PM_PI); joint[0] = q0; joint[1] = q1; joint[2] = D1 + D3 - D5 - z; joint[3] = c - ( q0 + q1); joint[4] = world->a; joint[5] = world->b; if(DX==1){*fflags = 1;} else{*fflags = 0;} return (0); } // scaraKinematicsInverse()