35 double x0, x1, x2, x3;
36 double y0, y1, y2, y3;
37 double z0, z1, z2, z3;
39 angles current_angles(current_encoders.size());
40 for(
unsigned int z = 0; z < current_angles.size(); ++z) {
45 current_angles[1] = current_angles[1] -
M_PI/2.0;
46 current_angles[2] = current_angles[2] -
M_PI;
47 current_angles[3] = M_PI - current_angles[3];
48 current_angles[5] = -current_angles[5];
52 angles cx(current_angles.size()), sx(current_angles.size());
53 angles::iterator cx_iter, sx_iter;
57 angle[2] = angle[1]+angle[2];
58 angle[3] = angle[2]+angle[3];
70 x3 = -cx[0]*cx[3]*cx[4]-sx[0]*sx[4];
77 y3 = -sx[0]*cx[3]*cx[4]+cx[0]*sx[4];
78 pose[1] = y0*_length[0]+y1*_length[1]+y2*_length[2]+y3*_length[3];
85 pose[2] = z0*_length[0]+z1*_length[1]+z2*_length[2]+z3*_length[3];
89 pose[4] = acos(cx[4]*sx[3]);
94 const double theta1 = angle[0];
95 const double theta5 = angle[4];
96 const double theta6 = angle[5];
97 const double theta234 = angle[3];
103 double R11 = -sin(theta1)*cos(theta5) *sin(theta6) + cos(theta1)*(sin(theta234)*cos(theta6)+cos(theta234)*sin(theta5)*sin(theta6));
104 double R21 = sin(theta1)*sin(theta234)*cos(theta6) + sin(theta6)*(cos(theta1) *cos(theta5)+cos(theta234)*sin(theta1)*sin(theta5));
109 v2[1] = M_PI - v2[0];
117 const double R13 = -cos(theta1)*cos(theta234)*cos(theta5) - sin(theta1)*sin(theta5);
118 const double R23 = -sin(theta1)*cos(theta234)*cos(theta5) + cos(theta1)*sin(theta5);
119 pose[3] = atan2(R13, -R23);
122 const double R31 = cos(theta234)*cos(theta6) - sin(theta234)*sin(theta5)*sin(theta6);
123 const double R32 = -cos(theta234)*sin(theta6) - sin(theta234)*sin(theta5)*cos(theta6);
124 pose[5] = atan2(R31, R32);
132 assert( (length.size() == 4) &&
"You have to provide the metrics for exactly 4 links" );
133 assert( (parameters.size() == 6) &&
"You have to provide exactly 5 motor parameters" );
148 sqrt( ( -
pow2(p_gr.
z) ) *
163 sqrt( ( -
pow2(p_gr.
z) ) *
186 double xgr2, ygr2, zgr2;
206 zg = p.
z + ( _length[3] * cos(angle.
theta234) );
218 for(angles::const_iterator i = v1.begin(); i != v1.end(); ++i) {
219 for(angles::const_iterator j = v2.begin(); j != v2.end(); ++j) {
224 assert(!
"precondition for findFirstEqualAngle failed -> no equal angles found");
233 const double theta1 = angle.
theta1;
235 const double theta3 = angle.
theta3;
237 const double theta5 = angle.
theta5;
239 const double theta234 = angle.
theta234;
240 const double b1 = angle.
b1;
241 const double b2 = angle.
b2;
243 const double phi = pose[3];
244 const double theta = pose[4];
245 const double psi = pose[5];
249 theta4 = theta234 - theta2 - theta3;
252 theta2 = theta2+
M_PI;
253 theta4 = theta234 - theta2 - theta3;
256 const double R11 = cos(phi)*cos(psi) - sin(phi)*cos(theta)*sin(psi);
257 const double R21 = sin(phi)*cos(psi) + cos(phi)*cos(theta)*sin(psi);
259 std::vector<double> theta16c(2), theta16s(2);
263 theta16c[0] = acos(-R11);
264 theta16c[1] = -theta16c[0];
265 theta16s[0] = asin(-R21);
266 theta16s[1] =
M_PI - theta16s[0];
271 theta16c[0] = acos(-R11);
272 theta16c[1] = -theta16c[0];
273 theta16s[0] = asin(-R21);
274 theta16s[1] =
M_PI - theta16s[0];
279 assert(!
"Special case \"|theta234+(1/2)*pi| = 0\" detected, but no solution found");
284 theta16c[0] = acos(R11);
285 theta16c[1] = -theta16c[0];
286 theta16s[0] = asin(R21);
287 theta16s[1] =
M_PI - theta16s[0];
292 theta16c[0] = acos(R11);
293 theta16c[1] = -theta16c[0];
294 theta16s[0] = asin(R21);
295 theta16s[1] =
M_PI -theta16s[0];
299 assert(!
"Special case \"|theta234+(3/2)*pi| = 0\" detected, but no solution found");
304 const double R31 = sin(theta)*sin(psi);
305 const double R32 = sin(theta)*cos(psi);
307 const double temp1 = cos(theta234);
308 const double temp2 = -sin(theta234)*sin(theta5);
310 const double c = ( R31*temp1 + R32*temp2 ) / (
pow2(temp1) +
pow2(temp2) );
311 const double s = ( R31*temp2 - R32*temp1 ) / (
pow2(temp1) +
pow2(temp2) );
313 theta16c[0] = acos(c);
314 theta16c[1] = -theta16c[0];
315 theta16s[0] = asin(s);
316 theta16s[1] =
M_PI - theta16s[0];
330 double temp, xm2, ym2, zm2;
333 xm2 = cos(theta1)*temp;
334 ym2 = sin(theta1)*temp;
418 p_gr.
x =
_length[3]*sin(pose[4])*sin(pose[3]);
419 p_gr.
y = -
_length[3]*sin(pose[4])*cos(pose[3]);
422 p_m.
x = pose[0]-p_gr.
x;
423 p_m.
y = pose[1]-p_gr.
y;
424 p_m.
z = pose[2]-p_gr.
z;
427 angle[0].theta1 =
atan1(p_m.
x,p_m.
y);
428 angle[4].theta1 = angle[0].theta1+
M_PI;
433 angle[0].theta1=angle[0].theta1-2.0*
M_PI;
436 angle[0].theta1=angle[0].theta1+2.0*
M_PI;
439 angle[4].theta1=angle[4].theta1-2.0*
M_PI;
442 angle[4].theta1=angle[4].theta1+2.0*
M_PI;
451 angle[0].theta3 = acos(angle[0].costh3)-
M_PI;
453 angle[1].theta3 = -acos(angle[1].costh3)+
M_PI;
457 angle[2].theta1=angle[0].theta1;
458 angle[2].theta234=angle[0].theta234-
M_PI;
459 angle[2].theta5=
M_PI-angle[0].theta5;
463 angle[2].theta3 = acos(angle[2].costh3)-
M_PI;
465 angle[3].theta3 = -acos(angle[3].costh3)+
M_PI;
475 angle[4].theta3 = acos(angle[4].costh3)-
M_PI;
477 angle[5].theta3 = -acos(angle[5].costh3)+
M_PI;
481 angle[6].theta1=angle[4].theta1;
482 angle[6].theta234=angle[4].theta234-
M_PI;
483 angle[6].theta5=
M_PI-angle[4].theta5;
486 angle[6].theta3 = acos(angle[6].costh3)-
M_PI;
488 angle[7].theta3 = -acos(angle[7].costh3)+
M_PI;
491 for( ::std::vector<angles_calc>::iterator iter = angle.begin(); iter != angle.end(); ) {
492 if(
pow2(iter->costh3) <= 1.0) {
494 iter = angle.erase(iter);
499 iter = angle.erase(iter);
503 if(angle.size() == 0) {
507 ::std::vector< ::std::vector<int> > PossibleTargetsInEncoders;
508 for( ::std::vector<angles_calc>::iterator i = angle.begin(); i != angle.end(); ++i ) {
509 ::std::vector<int> solution(6);
517 PossibleTargetsInEncoders.push_back(solution);
521 ::std::vector< ::std::vector<int> >::const_iterator sol =
KinematicsDefaultEncMinAlgorithm()(PossibleTargetsInEncoders.begin(), PossibleTargetsInEncoders.end(), current_encoders.begin(), current_encoders.end());
523 assert( sol != PossibleTargetsInEncoders.end() &&
"All solutions are out of range");
526 encoders::iterator gripper_encoder_iter = std::copy( (*sol).begin(), (*sol).end(), solution );
_encT rad2enc(_angleT const &angle, _angleT const &angleOffset, _encT const &epc, _encT const &encOffset, _encT const &rotDir)
std::vector< double > angles
Being used to store angles (in radian).
void _setLength(metrics const &length)
void init(metrics const &length, parameter_container const ¶meters)
void DK(coordinates &solution, encoders const ¤t_encoders) const
_T anglereduce(const _T a)
void swap(Matrix &A, Matrix &B)
std::vector< angles_calc > angles_container
void IK_theta234theta5(angles_calc &angle, const position &p_gr) const
std::vector< KinematicParameters > parameter_container
void _setParameters(parameter_container const ¶meters)
static const int _nrOfPossibleSolutions
parameter_container _parameters
bool AnglePositionTest(const angles_calc &a) const
bool PositionTest6MS(const double &theta1, const double &theta2, const double &theta3, const double &theta234, const position &p) const
bool angledef(angles_calc &a) const
FloatVector FloatVector * a
_angleT enc2rad(_encT const &enc, _angleT const &angleOffset, _encT const &epc, _encT const &encOffset, _encT const &rotDir)
double findFirstEqualAngle(const angles &v1, const angles &v2) const
void IK(encoders::iterator solution, coordinates const &pose, encoders const &cur_angles) const
std::vector< double > coordinates
To store coordinates.
bool GripperTest(const position &p_gr, const angles_calc &angle) const
_T atan0(const _T in1, const _T in2)
std::vector< int > encoders
To store encoders.
void IK_b1b2costh3_6MS(angles_calc &a, const position &p) const
void thetacomp(angles_calc &a, const position &p_m, const coordinates &pose) const
static const double _tolerance
std::vector< double > metrics
To store metrics, 'aka' the length's of the different segments of the robot.