kinematics6M90G.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (C) 2008 by Neuronics AG *
3  * support@neuronics.ch *
4  ***************************************************************************/
5 
6 #include <kinematics6M90G.h>
7 
8 namespace AnaGuess {
9 
12  initialize();
13 }
16 
17 }
18 
20 std::vector<double> Kinematics6M90G::getLinkLength() {
21  std::vector<double> result(mSegmentLength);
22  return result;
23 }
25 std::vector<int> Kinematics6M90G::getEpc() {
26  std::vector<int> result(mEncodersPerCycle);
27  return result;
28 }
30 std::vector<int> Kinematics6M90G::getEncOff() {
31  std::vector<int> result(mEncoderOffset);
32  return result;
33 }
35 std::vector<int> Kinematics6M90G::getDir() {
36  std::vector<int> result(mRotationDirection);
37  return result;
38 }
40 std::vector<double> Kinematics6M90G::getAngOff() {
41  std::vector<double> result(mAngleOffset);
42  return result;
43 }
45 std::vector<double> Kinematics6M90G::getAngStop() {
46  std::vector<double> result(mAngleStop);
47  return result;
48 }
50 std::vector<double> Kinematics6M90G::getAngRange() {
51  std::vector<double> result;
52  double diff;
53  for (int i = 0; i < 6; i++) {
54  diff = mAngleStop[i] - mAngleOffset[i];
55  if (diff < 0) {
56  result.push_back(-diff);
57  } else {
58  result.push_back(diff);
59  }
60  }
61  return result;
62 }
64 std::vector<double> Kinematics6M90G::getAngMin() {
65  std::vector<double> result;
66  for (int i = 0; i < 6; i++) {
67  if (mAngleStop[i] < mAngleOffset[i]) {
68  result.push_back(mAngleStop[i]);
69  } else {
70  result.push_back(mAngleOffset[i]);
71  }
72  }
73  return result;
74 }
76 std::vector<double> Kinematics6M90G::getAngMax() {
77  std::vector<double> result;
78  for (int i = 0; i < 6; i++) {
79  if (mAngleStop[i] < mAngleOffset[i]) {
80  result.push_back(mAngleOffset[i]);
81  } else {
82  result.push_back(mAngleStop[i]);
83  }
84  }
85  return result;
86 }
87 
89 bool Kinematics6M90G::setLinkLength(const std::vector<double> aLengths) {
90  if ((int) aLengths.size() != mNumberOfSegments) {
91  return false;
92  }
93 
94  for (int i = 0; i < mNumberOfSegments; ++i) {
95  mSegmentLength[i] = aLengths.at(i);
96  }
97 
98  return true;
99 }
101 bool Kinematics6M90G::setAngOff(const std::vector<double> aAngOff) {
102  if ((int) aAngOff.size() != mNumberOfMotors) {
103  return false;
104  }
105 
106  for (int i = 0; i < mNumberOfMotors; ++i) {
107  mAngleOffset[i] = aAngOff.at(i);
108  }
109 
110  return true;
111 }
113 bool Kinematics6M90G::setAngStop(const std::vector<double> aAngStop) {
114  if ((int) aAngStop.size() != mNumberOfMotors) {
115  return false;
116  }
117 
118  for (int i = 0; i < mNumberOfMotors; ++i) {
119  mAngleStop[i] = aAngStop.at(i);
120  }
121 
122  return true;
123 }
124 
126 bool Kinematics6M90G::enc2rad(std::vector<double>& aAngles, const std::vector<int> aEncoders) {
127  for(int i = 0; i < 6; ++i) {
128  aAngles[i] = MHF::enc2rad(aEncoders[i], mAngleOffset[i], mEncodersPerCycle[i], mEncoderOffset[i], mRotationDirection[i]);
129  }
130  return true;
131 }
133 bool Kinematics6M90G::rad2enc(std::vector<int>& aEncoders, const std::vector<double> aAngles) {
134  for(int i = 0; i < 6; ++i ) {
135  aEncoders[i] = MHF::rad2enc(aAngles[i], mAngleOffset[i], mEncodersPerCycle[i], mEncoderOffset[i], mRotationDirection[i]);
136  }
137  return true;
138 }
139 
141 bool Kinematics6M90G::directKinematics(std::vector<double>& aPosition, const std::vector<double> aAngles) {
142  if(!mIsInitialized) {
143  initialize();
144  }
145 
146  // numering the angles starting by 0-5
147 
148  double x0, x1, x2, x3;
149  double y0, y1, y2, y3;
150  double z0, z1, z2, z3;
151  double R13, R23, R33, R31, R32;
152 
153  std::vector<double> current_angles(6);
154  for(int i = 0; i < 6; ++i) {
155  current_angles[i] = aAngles[i];
156  }
157 
158  // needs refactoring:
159  current_angles[1] = current_angles[1] - MHF_PI/2.0;
160  current_angles[2] = current_angles[2] - MHF_PI;
161  current_angles[3] = MHF_PI - current_angles[3];
162 
163  std::vector<double> pose(6);
164 
165  std::vector<double> cx(current_angles.size()), sx(current_angles.size());
166  std::vector<double>::iterator cx_iter, sx_iter;
167 
168  std::vector<double> angle = current_angles;
169 
170  angle[2] = angle[1]+angle[2];
171  angle[3] = angle[2]+angle[3];
172 
173  cx_iter = cx.begin();
174  sx_iter = sx.begin();
175  std::transform(angle.begin(), angle.end(), sx_iter, MHF::unary_precalc_sin<double>() );
176  std::transform(angle.begin(), angle.end(), cx_iter, MHF::unary_precalc_cos<double>() );
177 
178  R13 = (-1*cx[0]*cx[3]*cx[4])-(sx[0]*sx[4]);
179  R23 = (-1*sx[0]*cx[3]*cx[4])+(cx[0]*sx[4]);
180  R33 = sx[3]*cx[4];
181  R31 = cx[3];
182  R32 =(-1)*sx[3]*sx[4];
183 
184  //x
185  x0 = cx[0]*sx[1];
186  x1 = cx[0]*sx[2];
187  x2 = cx[0]*sx[3];
188  x3 = -cx[0]*cx[3]*cx[4]-sx[0]*sx[4];
189  pose[0] = x0*mSegmentLength[0]+x1*mSegmentLength[1]+x2*mSegmentLength[2]+x3*mSegmentLength[3];
190 
191  //y
192  y0 = sx[0]*sx[1];
193  y1 = sx[0]*sx[2];
194  y2 = sx[0]*sx[3];
195  y3 = -sx[0]*cx[3]*cx[4]+cx[0]*sx[4];
196  pose[1] = y0*mSegmentLength[0]+y1*mSegmentLength[1]+y2*mSegmentLength[2]+y3*mSegmentLength[3];
197 
198  //z
199  z0 = cx[1];
200  z1 = cx[2];
201  z2 = cx[3];
202  z3 = cx[4]*sx[3];
203  pose[2] = z0*mSegmentLength[0]+z1*mSegmentLength[1]+z2*mSegmentLength[2]+z3*mSegmentLength[3];
204 
205  // phi, theta, psi
206  pose[4] = acos(R33);
207  if(pose[4]==0) {
208  pose[3] = atan2(pose[1],pose[0]);
209  pose[5] = 0;
210  } else if(pose[4]==MHF_PI) {
211  pose[3] = atan2(pose[1],pose[0])+MHF_PI/2;
212  pose[5] = MHF_PI/2;
213  } else {
214  pose[3] = atan2(R13,-R23);
215  pose[5] = atan2(R31,R32);
216  }
217 
218 
219  std::swap(aPosition, pose);
220  return true;
221 }
223 bool Kinematics6M90G::inverseKinematics(std::vector<double>& aAngles, const std::vector<double> aPosition,
224  const std::vector<double> aStartingAngles) {
225  if(!mIsInitialized) {
226  initialize();
227  }
228 
229  // aPosition: Winkel Deg->Rad
230  // Alle 8 Loeungen werden in einem Array angle, welches aus 8 Structs besteht, gespeichert:
231  // 0-3 fr theta1_1
232  // 4-7 fr theta1_2
233 
234  // Declaration
235  position p_gr;
236  position p_m;
238 
239  // calculation of the gripper vector
240  p_gr.x = mSegmentLength[3]*sin(aPosition[4])*sin(aPosition[3]);
241  p_gr.y = -mSegmentLength[3]*sin(aPosition[4])*cos(aPosition[3]);
242  p_gr.z = mSegmentLength[3]*cos(aPosition[4]);
243 
244  p_m.x = aPosition[0]-p_gr.x;
245  p_m.y = aPosition[1]-p_gr.y;
246  p_m.z = aPosition[2]-p_gr.z;
247 
248  // calculate theta1_1 and theta1_2
249  angle[0].theta1 = MHF::atan1(p_m.x,p_m.y);
250  angle[4].theta1 = angle[0].theta1+MHF_PI;
251 
252 
253  // check the borders according to the settings
254  if(angle[0].theta1>mAngleStop[0])
255  angle[0].theta1=angle[0].theta1-2.0*MHF_PI;
256 
257  if(angle[0].theta1<mAngleOffset[0])
258  angle[0].theta1=angle[0].theta1+2.0*MHF_PI;
259 
260  if(angle[4].theta1>mAngleStop[0])
261  angle[4].theta1=angle[4].theta1-2.0*MHF_PI;
262 
263  if(angle[4].theta1<mAngleOffset[0])
264  angle[4].theta1=angle[4].theta1+2.0*MHF_PI;
265 
266 
267  //====THETA1_1==================
268  //-------THETA234_1-------------
269  IK_theta234theta5(angle[0], p_gr);
270  IK_b1b2costh3_6MS(angle[0], p_m);
271 
272  angle[1]=angle[0];
273  angle[0].theta3 = acos(angle[0].costh3)-MHF_PI;
274  thetacomp(angle[0], p_m);
275  angle[1].theta3 = -acos(angle[1].costh3)+MHF_PI;
276  thetacomp(angle[1], p_m);
277 
278  //-------THETA234_2-------------
279  angle[2].theta1=angle[0].theta1;
280  angle[2].theta234=angle[0].theta234-MHF_PI;
281  angle[2].theta5=MHF_PI-angle[0].theta5;
282 
283  IK_b1b2costh3_6MS(angle[2], p_m);
284  angle[3]=angle[2];
285  angle[2].theta3 = acos(angle[2].costh3)-MHF_PI;
286  thetacomp(angle[2], p_m);
287  angle[3].theta3 = -acos(angle[3].costh3)+MHF_PI;
288  thetacomp(angle[3], p_m);
289 
290 
291  //====THETA1_2==================
292  //-------THETA234_1-------------
293  IK_theta234theta5(angle[4], p_gr);
294  IK_b1b2costh3_6MS(angle[4], p_m);
295 
296  angle[5]=angle[4];
297  angle[4].theta3 = acos(angle[4].costh3)-MHF_PI;
298  thetacomp(angle[4], p_m);
299  angle[5].theta3 = -acos(angle[5].costh3)+MHF_PI;
300  thetacomp(angle[5], p_m);
301 
302  //-------THETA234_2-------------
303  angle[6].theta1=angle[4].theta1;
304  angle[6].theta234=angle[4].theta234-MHF_PI;
305  angle[6].theta5=MHF_PI-angle[4].theta5;
306  IK_b1b2costh3_6MS(angle[6], p_m);
307  angle[7]=angle[6];
308  angle[6].theta3 = acos(angle[6].costh3)-MHF_PI;
309  thetacomp(angle[6], p_m);
310  angle[7].theta3 = -acos(angle[7].costh3)+MHF_PI;
311  thetacomp(angle[7], p_m);
312 
313  // delete solutions out of range (in joint space)
314  for( ::std::vector<angles_calc>::iterator iter = angle.begin(); iter != angle.end(); /* do iter forward in body */ ) {
315  if( MHF::pow2(iter->costh3) <= 1.0) {
316  if(!angledef(*iter))
317  iter = angle.erase(iter);
318  else
319  ++iter;
320  continue;
321  }
322  iter = angle.erase(iter);
323  }
324 
325 
326  // check if solutions in range left
327  if(angle.size() == 0) {
328  throw NoSolutionException();
329  }
330 
331  // store possible solution angles to std::vector<std::vector<double>>
332  std::vector< std::vector<double> > PossibleTargets;
333  for( std::vector<angles_calc>::iterator i = angle.begin(); i != angle.end(); ++i ) {
334  std::vector<double> possangles(5);
335 
336  possangles[0] = i->theta1;
337  possangles[1] = i->theta2;
338  possangles[2] = i->theta3;
339  possangles[3] = i->theta4;
340  possangles[4] = i->theta5;
341 
342  PossibleTargets.push_back(possangles);
343  }
344 
345  // choose best solution
346  std::vector< std::vector<double> >::const_iterator sol = KinematicsDefaultRadMinAlgorithm()(PossibleTargets.begin(), PossibleTargets.end(), aStartingAngles.begin(), aStartingAngles.end());
347 
348  if(sol == PossibleTargets.end()) {
349  throw NoSolutionException();
350  }
351 
352  // copy solution to aAngles vector
353  for (int i = aAngles.size(); i < 6; ++i)
354  aAngles.push_back(0.0);
355  std::vector<double>::iterator gripper_iter = std::copy( (*sol).begin(), (*sol).end(), aAngles.begin() );
356  *gripper_iter = aStartingAngles[5]; // copy gripper-angle from current
357 
358  return true;
359 }
362  // NOTE: data for Katana6M90A with angle gripper
363 
364  mIsInitialized = false;
365 
366  //fill in segment data
367  mNumberOfSegments = 4;
368 
369  mSegmentLength.push_back(190.0);
370  mSegmentLength.push_back(139.0);
371  mSegmentLength.push_back(147.3);
372  mSegmentLength.push_back(150.5);
373 
374  //fill in joint data
375  mNumberOfMotors = 6;
376 
377  mAngleOffset.push_back(0.116064);
378  mAngleStop.push_back(6.154904);
379  mEncodersPerCycle.push_back(51200);
380  mEncoderOffset.push_back(31000);
381  mRotationDirection.push_back(1);
382 
383  mAngleOffset.push_back(2.168572);
384  mAngleStop.push_back(-0.274889);
385  mEncodersPerCycle.push_back(94976);
386  mEncoderOffset.push_back(-31000);
387  mRotationDirection.push_back(1);
388 
389  mAngleOffset.push_back(0.919789);
390  mAngleStop.push_back(5.283112);
391  mEncodersPerCycle.push_back(47488);
392  mEncoderOffset.push_back(-31000);
393  mRotationDirection.push_back(-1);
394 
395  mAngleOffset.push_back(1.108284);
396  mAngleStop.push_back(5.122541);
397  mEncodersPerCycle.push_back(51200);
398  mEncoderOffset.push_back(31000);
399  mRotationDirection.push_back(1);
400 
401  mAngleOffset.push_back(0.148353); // for 6M90B: -2.99324
402  mAngleStop.push_back(6.117379); // for 6M90B: 2.975787
403  mEncodersPerCycle.push_back(51200);
404  mEncoderOffset.push_back(31000);
405  mRotationDirection.push_back(1);
406 
407  mAngleOffset.push_back(-2.085668);
408  mAngleStop.push_back(3.656465);
409  mEncodersPerCycle.push_back(51200);
410  mEncoderOffset.push_back(31000);
411  mRotationDirection.push_back(1);
412 
413  mIsInitialized = true;
414 
415  return mIsInitialized;
416 }
419  angle.theta234 = -MHF::acotan( ( (p_gr.x * p_gr.z * cos(angle.theta1) ) -
420  sqrt( ( -MHF::pow2(p_gr.z) ) *
421  ( -MHF::pow2(mSegmentLength[3]) + MHF::pow2(p_gr.x) + MHF::pow2(p_gr.z) ) * MHF::pow2(sin(angle.theta1))
422  )
423  ) / MHF::pow2(p_gr.z)
424  );
425 
426  angle.theta5 = acos( p_gr.z/(mSegmentLength[3]*sin(angle.theta234)) );
427 
428  if(p_gr.z==0) {
429  angle.theta234=0;
430  angle.theta5=angle.theta1-MHF::atan1(-p_gr.x,-p_gr.y);
431  }
432 
433  bool griptest;
434  griptest = GripperTest(p_gr, angle);
435  if(!griptest) {
436  angle.theta5=-angle.theta5;
437  griptest=GripperTest(p_gr, angle);
438  if(!griptest) {
439  angle.theta234 = -MHF::acotan( ( ( p_gr.x * p_gr.z * cos(angle.theta1) ) +
440  sqrt( ( -MHF::pow2(p_gr.z) ) *
441  ( -MHF::pow2(mSegmentLength[3]) + MHF::pow2(p_gr.x) + MHF::pow2(p_gr.z) ) * MHF::pow2(sin(angle.theta1))
442  )
443  ) / MHF::pow2(p_gr.z)
444  );
445  angle.theta5 = acos( p_gr.z / (mSegmentLength[3]*sin(angle.theta234)) );
446  if(p_gr.z==0) {
447  angle.theta234=-MHF_PI;
448  angle.theta5=MHF::atan1(p_gr.x,p_gr.y) - angle.theta1;
449  }
450 
451  griptest=GripperTest(p_gr, angle);
452  if(!griptest) {
453  angle.theta5=-angle.theta5;
454  }
455  }
456  }
457 
458 }
460 bool Kinematics6M90G::GripperTest(const position &p_gr, const angles_calc &angle) const {
461  double xgr2, ygr2, zgr2;
462 
463  xgr2 = -mSegmentLength[3]*(cos(angle.theta1)*cos(angle.theta234)*cos(angle.theta5)+sin(angle.theta1)*sin(angle.theta5));
464  ygr2 = -mSegmentLength[3]*(sin(angle.theta1)*cos(angle.theta234)*cos(angle.theta5)-cos(angle.theta1)*sin(angle.theta5));
465  zgr2 = mSegmentLength[3]*sin(angle.theta234)*cos(angle.theta5);
466 
467  if((MHF::pow2(p_gr.x-xgr2)+MHF::pow2(p_gr.y-ygr2)+MHF::pow2(p_gr.z-zgr2))>=cTolerance)
468  return false;
469 
470  return true;
471 }
474  double xg, yg, zg;
475  double d5 = mSegmentLength[2] + mSegmentLength[3];
476  xg = p.x + ( mSegmentLength[3] * cos(angle.theta1) * sin(angle.theta234) );
477  yg = p.y + ( mSegmentLength[3] * sin(angle.theta1) * sin(angle.theta234) );
478  zg = p.z + ( mSegmentLength[3] * cos(angle.theta234) );
479 
480 
481  angle.b1 = xg*cos(angle.theta1) + yg*sin(angle.theta1) - d5*sin(angle.theta234);
482  angle.b2 = zg - d5*cos(angle.theta234);
483  angle.costh3 = -( MHF::pow2(angle.b1) + MHF::pow2(angle.b2) - MHF::pow2(mSegmentLength[0]) - MHF::pow2(mSegmentLength[1]) ) / ( 2.0*mSegmentLength[0]*mSegmentLength[1] );
484 
485 }
488  angle.theta2 = -MHF_PI/2.0 - ( MHF::atan0(angle.b1,angle.b2)+MHF::atan0(mSegmentLength[0]+mSegmentLength[1]*cos(angle.theta3),mSegmentLength[1]*sin(angle.theta3)) );
489  angle.theta4 = angle.theta234-angle.theta2-angle.theta3;
490 
491  if(!PositionTest6MS(angle,p_m)) {
492  angle.theta2 = angle.theta2+MHF_PI;
493  angle.theta4 = angle.theta234-angle.theta2-angle.theta3;
494  }
495 
496 }
499  double temp, xm2, ym2, zm2;
500 
501  temp = mSegmentLength[0]*sin(a.theta2)+mSegmentLength[1]*sin(a.theta2+a.theta3)+mSegmentLength[2]*sin(a.theta234);
502  xm2 = cos(a.theta1)*temp;
503  ym2 = sin(a.theta1)*temp;
504  zm2 = mSegmentLength[0]*cos(a.theta2)+mSegmentLength[1]*cos(a.theta2+a.theta3)+mSegmentLength[2]*cos(a.theta234);
505 
506  if((MHF::pow2(p.x-xm2)+MHF::pow2(p.y-ym2)+MHF::pow2(p.z-zm2))>=cTolerance)
507  return false;
508 
509  return true;
510 }
513  // constants here. needs refactoring:
518 
519  if(a.theta1>mAngleStop[0]) {
520  a.theta1=a.theta1-2.0*MHF_PI;
521  }
522  if(a.theta2>MHF_PI) {
523  a.theta2=a.theta2-2.0*MHF_PI;
524  }
525  if(a.theta5<mAngleOffset[4]) {
526  a.theta5=a.theta5+2.0*MHF_PI;
527  }
528 
529  return AnglePositionTest(a);
530 
531 }
534 
535  if( (a.theta1+0.0087<mAngleOffset[0])||(a.theta1>mAngleStop[0]) )
536  return false;
537 
538  if( (a.theta2-0.0087>mAngleOffset[1])||(a.theta2<mAngleStop[1]) )
539  return false;
540 
541  if( (a.theta3<mAngleOffset[2])||(a.theta3>mAngleStop[2]) )
542  return false;
543 
544  if( (a.theta4<mAngleOffset[3])||(a.theta4>mAngleStop[3]) )
545  return false;
546 
547  if( (a.theta5<mAngleOffset[4])||(a.theta5>mAngleStop[4]) )
548  return false;
549 
550  return true;
551 }
553 } // namespace
std::vector< angles_calc > angles_container
std::vector< int > mEncodersPerCycle
Encoders per cycle vector.
void IK_b1b2costh3_6MS(angles_calc &angle, const position &p) const
std::vector< int > mEncoderOffset
Encoder offset vector.
bool initialize()
initialization routine
std::vector< int > getDir()
get direction
std::vector< double > getAngStop()
get angle stop
void thetacomp(angles_calc &angle, const position &p_m) const
std::vector< double > getAngOff()
get angle offset
std::vector< double > getAngMax()
get angle max
bool inverseKinematics(std::vector< double > &aAngles, const std::vector< double > aPosition, const std::vector< double > aStartingAngles)
bool rad2enc(std::vector< int > &aEncoders, const std::vector< double > aAngles)
void swap(Matrix &A, Matrix &B)
Definition: newmat.h:2159
bool directKinematics(std::vector< double > &aPosition, const std::vector< double > aAngles)
FloatVector * pose
std::vector< double > getAngRange()
get angle range
void IK_theta234theta5(angles_calc &angle, const position &p_gr) const
helper functions
bool AnglePositionTest(const angles_calc &a) const
_encT rad2enc(_angleT const &angle, _angleT const &angleOffset, _encT const &epc, _encT const &encOffset, _encT const &rotDir)
structs, type and constants used in inverse kinematics calculation
std::vector< double > mAngleStop
Angle stop vector [rad].
bool setAngOff(const std::vector< double > aAngOff)
set angle offset
std::vector< int > mRotationDirection
Rotation direction vector [1|-1].
bool GripperTest(const position &p_gr, const angles_calc &angle) const
std::vector< int > getEpc()
get encoders per cycle
std::vector< double > mAngleOffset
Angle offset vector [rad].
bool setLinkLength(const std::vector< double > aLengths)
set link length
bool setAngStop(const std::vector< double > aAngStop)
set angle offset
bool enc2rad(std::vector< double > &aAngles, const std::vector< int > aEncoders)
FloatVector FloatVector * a
FloatVector * angle
bool mIsInitialized
Initialized flag.
std::vector< int > getEncOff()
get encoder offset
int mNumberOfMotors
Number of motors of the robot.
_angleT enc2rad(_encT const &enc, _angleT const &angleOffset, _encT const &epc, _encT const &encOffset, _encT const &rotDir)
bool angledef(angles_calc &a) const
bool PositionTest6MS(const angles_calc &a, const position &p) const
static const int cNrOfPossibleSolutions
std::vector< double > getLinkLength()
get link length
std::vector< double > getAngMin()
get angle min
int mNumberOfSegments
Number of segments of the robot.
std::vector< double > mSegmentLength
Effector segment lengths vector [m].


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:44