moveit2
The MoveIt Motion Planning Framework for ROS 2.
prbt_manipulator_ikfast_solver.cpp
Go to the documentation of this file.
1 #define IKFAST_HAS_LIBRARY
25 #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
26 using namespace ikfast;
27 
28 // check if the included ikfast version matches what this file was compiled with
29 static_assert(IKFAST_VERSION==61); // version found in ikfast.h
30 
31 #include <cmath>
32 #include <vector>
33 #include <limits>
34 #include <algorithm>
35 #include <complex>
36 
37 #ifndef IKFAST_ASSERT
38 #include <stdexcept>
39 #include <sstream>
40 #include <iostream>
41 
42 #ifdef _MSC_VER
43 #ifndef __PRETTY_FUNCTION__
44 #define __PRETTY_FUNCTION__ __FUNCDNAME__
45 #endif
46 #endif
47 
48 #ifndef __PRETTY_FUNCTION__
49 #define __PRETTY_FUNCTION__ __func__
50 #endif
51 
52 #define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } }
53 
54 #endif
55 
56 #if defined(_MSC_VER)
57 #define IKFAST_ALIGNED16(x) __declspec(align(16)) x
58 #else
59 #define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
60 #endif
61 
62 #define IK2PI ((IkReal)6.28318530717959)
63 #define IKPI ((IkReal)3.14159265358979)
64 #define IKPI_2 ((IkReal)1.57079632679490)
65 
66 #ifdef _MSC_VER
67 #ifndef isnan
68 #define isnan _isnan
69 #endif
70 #ifndef isinf
71 #define isinf _isinf
72 #endif
73 //#ifndef isfinite
74 //#define isfinite _isfinite
75 //#endif
76 #endif // _MSC_VER
77 
78 using namespace std; // necessary to get std math routines
79 
80 #ifdef IKFAST_NAMESPACE
81 namespace IKFAST_NAMESPACE {
82 #endif
83 
84 inline float IKabs(float f) { return fabsf(f); }
85 inline double IKabs(double f) { return fabs(f); }
86 
87 inline float IKsqr(float f) { return f*f; }
88 inline double IKsqr(double f) { return f*f; }
89 
90 inline float IKlog(float f) { return logf(f); }
91 inline double IKlog(double f) { return log(f); }
92 
93 // allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation
94 #ifndef IKFAST_SINCOS_THRESH
95 #define IKFAST_SINCOS_THRESH ((IkReal)1e-7)
96 #endif
97 
98 // used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation
99 #ifndef IKFAST_ATAN2_MAGTHRESH
100 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7)
101 #endif
102 
103 // minimum distance of separate solutions
104 #ifndef IKFAST_SOLUTION_THRESH
105 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
106 #endif
107 
108 // there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate
109 #ifndef IKFAST_EVALCOND_THRESH
110 #define IKFAST_EVALCOND_THRESH ((IkReal)0.00001)
111 #endif
112 
113 
114 inline float IKasin(float f)
115 {
116 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
117 if( f <= -1 ) return float(-IKPI_2);
118 else if( f >= 1 ) return float(IKPI_2);
119 return asinf(f);
120 }
121 inline double IKasin(double f)
122 {
123 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
124 if( f <= -1 ) return -IKPI_2;
125 else if( f >= 1 ) return IKPI_2;
126 return asin(f);
127 }
128 
129 // return positive value in [0,y)
130 inline float IKfmod(float x, float y)
131 {
132  while(x < 0) {
133  x += y;
134  }
135  return fmodf(x,y);
136 }
137 
138 // return positive value in [0,y)
139 inline double IKfmod(double x, double y)
140 {
141  while(x < 0) {
142  x += y;
143  }
144  return fmod(x,y);
145 }
146 
147 inline float IKacos(float f)
148 {
149 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
150 if( f <= -1 ) return float(IKPI);
151 else if( f >= 1 ) return float(0);
152 return acosf(f);
153 }
154 inline double IKacos(double f)
155 {
156 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
157 if( f <= -1 ) return IKPI;
158 else if( f >= 1 ) return 0;
159 return acos(f);
160 }
161 inline float IKsin(float f) { return sinf(f); }
162 inline double IKsin(double f) { return sin(f); }
163 inline float IKcos(float f) { return cosf(f); }
164 inline double IKcos(double f) { return cos(f); }
165 inline float IKtan(float f) { return tanf(f); }
166 inline double IKtan(double f) { return tan(f); }
167 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
168 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
169 inline float IKatan2Simple(float fy, float fx) {
170  return atan2f(fy,fx);
171 }
172 inline float IKatan2(float fy, float fx) {
173  if( isnan(fy) ) {
174  IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
175  return float(IKPI_2);
176  }
177  else if( isnan(fx) ) {
178  return 0;
179  }
180  return atan2f(fy,fx);
181 }
182 inline double IKatan2Simple(double fy, double fx) {
183  return atan2(fy,fx);
184 }
185 inline double IKatan2(double fy, double fx) {
186  if( isnan(fy) ) {
187  IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
188  return IKPI_2;
189  }
190  else if( isnan(fx) ) {
191  return 0;
192  }
193  return atan2(fy,fx);
194 }
195 
196 template <typename T>
198 {
199  T value;
200  bool valid;
201 };
202 
203 template <typename T>
204 inline CheckValue<T> IKatan2WithCheck(T fy, T fx, T /* unused */)
205 {
206  CheckValue<T> ret;
207  ret.valid = false;
208  ret.value = 0;
209  if( !isnan(fy) && !isnan(fx) ) {
211  ret.value = IKatan2Simple(fy,fx);
212  ret.valid = true;
213  }
214  }
215  return ret;
216 }
217 
218 inline float IKsign(float f) {
219  if( f > 0 ) {
220  return float(1);
221  }
222  else if( f < 0 ) {
223  return float(-1);
224  }
225  return 0;
226 }
227 
228 inline double IKsign(double f) {
229  if( f > 0 ) {
230  return 1.0;
231  }
232  else if( f < 0 ) {
233  return -1.0;
234  }
235  return 0;
236 }
237 
238 template <typename T>
240 {
241  CheckValue<T> ret;
242  ret.valid = true;
243  if( n == 0 ) {
244  ret.value = 1.0;
245  return ret;
246  }
247  else if( n == 1 )
248  {
249  ret.value = f;
250  return ret;
251  }
252  else if( n < 0 )
253  {
254  if( f == 0 )
255  {
256  ret.valid = false;
257  ret.value = (T)1.0e30;
258  return ret;
259  }
260  if( n == -1 ) {
261  ret.value = T(1.0)/f;
262  return ret;
263  }
264  }
265 
266  int num = n > 0 ? n : -n;
267  if( num == 2 ) {
268  ret.value = f*f;
269  }
270  else if( num == 3 ) {
271  ret.value = f*f*f;
272  }
273  else {
274  ret.value = 1.0;
275  while(num>0) {
276  if( num & 1 ) {
277  ret.value *= f;
278  }
279  num >>= 1;
280  f *= f;
281  }
282  }
283 
284  if( n < 0 ) {
285  ret.value = T(1.0)/ret.value;
286  }
287  return ret;
288 }
289 
292 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
293 IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27,x28,x29,x30,x31,x32,x33,x34,x35,x36,x37,x38,x39,x40,x41,x42,x43,x44,x45,x46;
294 x0=IKcos(j[0]);
295 x1=IKcos(j[1]);
296 x2=IKcos(j[2]);
297 x3=IKsin(j[1]);
298 x4=IKsin(j[2]);
299 x5=IKsin(j[3]);
300 x6=IKcos(j[3]);
301 x7=IKsin(j[0]);
302 x8=IKcos(j[5]);
303 x9=IKsin(j[5]);
304 x10=IKsin(j[4]);
305 x11=IKcos(j[4]);
306 x12=((1.0)*x7);
307 x13=((1.0)*x6);
308 x14=((0.307)*x7);
309 x15=((0.084)*x3);
310 x16=((0.084)*x7);
311 x17=((1.0)*x0);
312 x18=((1.0)*x10);
313 x19=((0.35)*x3);
314 x20=((0.084)*x6);
315 x21=((0.307)*x0);
316 x22=((0.084)*x0);
317 x23=(x1*x2);
318 x24=(x1*x4);
319 x25=((-1.0)*x6);
320 x26=(x2*x3);
321 x27=(x5*x7);
322 x28=(x3*x4);
323 x29=(x10*x6);
324 x30=(x17*x5);
325 x31=((1.0)*x26);
326 x32=((((-1.0)*x31))+x24);
327 x33=((((-1.0)*x24))+x31);
328 x34=((((1.0)*x23))+(((1.0)*x28)));
329 x35=(x11*x32);
330 x36=(x33*x5);
331 x37=(x17*(((((-1.0)*x24))+x26)));
332 x38=(x12*(((((-1.0)*x24))+x26)));
333 x39=(x17*(((((-1.0)*x23))+(((-1.0)*x28)))));
334 x40=(x12*(((((-1.0)*x23))+(((-1.0)*x28)))));
335 x41=(x10*x38);
336 x42=(x39*x5);
337 x43=(x39*x6);
338 x44=(((x0*x6))+((x40*x5)));
339 x45=(x30+((x25*x40)));
340 x46=(x11*x45);
341 eerot[0]=(((x9*(((((-1.0)*x12*x6))+x42))))+((x8*((((x10*x37))+((x11*(((((-1.0)*x27))+((x25*x39)))))))))));
342 eerot[1]=((((-1.0)*x9*((((x18*x37))+(((1.0)*x11*(((((-1.0)*x12*x5))+(((-1.0)*x13*x39))))))))))+((x8*((x42+((x25*x7)))))));
343 eerot[2]=(((x10*((x43+x27))))+((x11*x37)));
344 IkReal x47=((1.0)*x24);
345 eetrans[0]=(((x21*x26))+((x0*x19))+((x11*(((((-1.0)*x22*x47))+((x0*x15*x2))))))+(((-1.0)*x21*x47))+((x10*((((x20*x39))+((x16*x5)))))));
346 eerot[3]=(((x44*x9))+((x8*((x46+x41)))));
347 eerot[4]=(((x9*(((((-1.0)*x41))+(((-1.0)*x46))))))+((x44*x8)));
348 eerot[5]=(((x10*(((((-1.0)*x30))+((x40*x6))))))+((x11*x38)));
349 IkReal x48=((1.0)*x24);
350 eetrans[1]=(((x19*x7))+((x14*x26))+((x10*((((x20*x40))+(((-1.0)*x22*x5))))))+((x11*(((((-1.0)*x16*x48))+((x15*x2*x7))))))+(((-1.0)*x14*x48)));
351 eerot[6]=(((x8*((((x10*x34))+((x35*x6))))))+((x36*x9)));
352 eerot[7]=(((x9*(((((-1.0)*x18*x34))+(((-1.0)*x13*x35))))))+((x36*x8)));
353 eerot[8]=(((x29*x33))+((x11*x34)));
354 eetrans[2]=((0.2604)+(((0.35)*x1))+((x29*(((((-0.084)*x24))+((x15*x2))))))+((x11*(((((0.084)*x23))+((x15*x4))))))+(((0.307)*x23))+(((0.307)*x28)));
355 }
356 
357 IKFAST_API int GetNumFreeParameters() { return 0; }
358 IKFAST_API int* GetFreeParameters() { return nullptr; }
359 IKFAST_API int GetNumJoints() { return 6; }
360 
361 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
362 
363 IKFAST_API int GetIkType() { return 0x67000001; }
364 
365 class IKSolver {
366 public:
367 IkReal j0,cj0,sj0,htj0,j0mul,j1,cj1,sj1,htj1,j1mul,j2,cj2,sj2,htj2,j2mul,j3,cj3,sj3,htj3,j3mul,j4,cj4,sj4,htj4,j4mul,j5,cj5,sj5,htj5,j5mul,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_r10,r10,rxp1_0,new_r11,r11,rxp1_1,new_r12,r12,rxp1_2,new_r20,r20,rxp2_0,new_r21,r21,rxp2_1,new_r22,r22,rxp2_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp;
368 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5;
369 
370 IkReal j100, cj100, sj100;
371 unsigned char _ij100[2], _nj100;
372  bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* /* unused */, IkSolutionListBase<IkReal>& solutions) {
373 j0=numeric_limits<IkReal>::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits<IkReal>::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits<IkReal>::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits<IkReal>::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits<IkReal>::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; j5=numeric_limits<IkReal>::quiet_NaN(); _ij5[0] = -1; _ij5[1] = -1; _nj5 = -1;
374 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
375  solutions.Clear();
376 r00 = eerot[0*3+0];
377 r01 = eerot[0*3+1];
378 r02 = eerot[0*3+2];
379 r10 = eerot[1*3+0];
380 r11 = eerot[1*3+1];
381 r12 = eerot[1*3+2];
382 r20 = eerot[2*3+0];
383 r21 = eerot[2*3+1];
384 r22 = eerot[2*3+2];
385 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
386 
387 new_r00=r00;
388 new_r01=r01;
389 new_r02=r02;
390 new_px=(px+(((-0.084)*r02)));
391 new_r10=r10;
392 new_r11=r11;
393 new_r12=r12;
394 new_py=(py+(((-0.084)*r12)));
395 new_r20=r20;
396 new_r21=r21;
397 new_r22=r22;
398 new_pz=((-0.2604)+pz+(((-0.084)*r22)));
399 r00 = new_r00; r01 = new_r01; r02 = new_r02; r10 = new_r10; r11 = new_r11; r12 = new_r12; r20 = new_r20; r21 = new_r21; r22 = new_r22; px = new_px; py = new_py; pz = new_pz;
400 IkReal x49=((1.0)*px);
401 IkReal x50=((1.0)*pz);
402 IkReal x51=((1.0)*py);
403 pp=((px*px)+(py*py)+(pz*pz));
404 npx=(((px*r00))+((py*r10))+((pz*r20)));
405 npy=(((px*r01))+((py*r11))+((pz*r21)));
406 npz=(((px*r02))+((py*r12))+((pz*r22)));
407 rxp0_0=((((-1.0)*r20*x51))+((pz*r10)));
408 rxp0_1=(((px*r20))+(((-1.0)*r00*x50)));
409 rxp0_2=((((-1.0)*r10*x49))+((py*r00)));
410 rxp1_0=((((-1.0)*r21*x51))+((pz*r11)));
411 rxp1_1=(((px*r21))+(((-1.0)*r01*x50)));
412 rxp1_2=((((-1.0)*r11*x49))+((py*r01)));
413 rxp2_0=(((pz*r12))+(((-1.0)*r22*x51)));
414 rxp2_1=(((px*r22))+(((-1.0)*r02*x50)));
415 rxp2_2=((((-1.0)*r12*x49))+((py*r02)));
416 {
417 IkReal j2array[2], cj2array[2], sj2array[2];
418 bool j2valid[2]={false};
419 _nj2 = 2;
420 cj2array[0]=((-1.00860400186133)+(((4.65332712889716)*pp)));
421 if( cj2array[0] >= -1-IKFAST_SINCOS_THRESH && cj2array[0] <= 1+IKFAST_SINCOS_THRESH )
422 {
423  j2valid[0] = j2valid[1] = true;
424  j2array[0] = IKacos(cj2array[0]);
425  sj2array[0] = IKsin(j2array[0]);
426  cj2array[1] = cj2array[0];
427  j2array[1] = -j2array[0];
428  sj2array[1] = -sj2array[0];
429 }
430 else if( isnan(cj2array[0]) )
431 {
432  // probably any value will work
433  j2valid[0] = true;
434  cj2array[0] = 1; sj2array[0] = 0; j2array[0] = 0;
435 }
436 for(int ij2 = 0; ij2 < 2; ++ij2)
437 {
438 if( !j2valid[ij2] )
439 {
440  continue;
441 }
442 _ij2[0] = ij2; _ij2[1] = -1;
443 for(int iij2 = ij2+1; iij2 < 2; ++iij2)
444 {
445 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
446 {
447  j2valid[iij2]=false; _ij2[1] = iij2; break;
448 }
449 }
450 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
451 
452 {
453 IkReal j0eval[1];
454 j0eval[0]=((IKabs(px))+(IKabs(py)));
455 if( IKabs(j0eval[0]) < 0.0000010000000000 )
456 {
457 {
458 IkReal j1eval[2];
459 j1eval[0]=((IKabs(sj2))+(((3.25732899022801)*(IKabs(((0.35)+(((0.307)*cj2))))))));
460 j1eval[1]=((1.29974853844603)+(sj2*sj2)+(cj2*cj2)+(((2.28013029315961)*cj2)));
461 if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 )
462 {
463 continue; // no branches [j0, j1]
464 
465 } else
466 {
467 {
468 IkReal j1array[2], cj1array[2], sj1array[2];
469 bool j1valid[2]={false};
470 _nj1 = 2;
471 IkReal x52=((0.35)+(((0.307)*cj2)));
472 CheckValue<IkReal> x55 = IKatan2WithCheck(IkReal(x52),IkReal(((0.307)*sj2)),IKFAST_ATAN2_MAGTHRESH);
473 if(!x55.valid){
474 continue;
475 }
476 IkReal x53=((1.0)*(x55.value));
477 if((((((0.094249)*(sj2*sj2)))+(x52*x52))) < -0.00001)
478 continue;
479 CheckValue<IkReal> x56=IKPowWithIntegerCheck(IKabs(IKsqrt(((((0.094249)*(sj2*sj2)))+(x52*x52)))),-1);
480 if(!x56.valid){
481 continue;
482 }
483 if( ((pz*(x56.value))) < -1-IKFAST_SINCOS_THRESH || ((pz*(x56.value))) > 1+IKFAST_SINCOS_THRESH )
484  continue;
485 IkReal x54=IKasin((pz*(x56.value)));
486 j1array[0]=(x54+(((-1.0)*x53)));
487 sj1array[0]=IKsin(j1array[0]);
488 cj1array[0]=IKcos(j1array[0]);
489 j1array[1]=((3.14159265358979)+(((-1.0)*x53))+(((-1.0)*x54)));
490 sj1array[1]=IKsin(j1array[1]);
491 cj1array[1]=IKcos(j1array[1]);
492 if( j1array[0] > IKPI )
493 {
494  j1array[0]-=IK2PI;
495 }
496 else if( j1array[0] < -IKPI )
497 { j1array[0]+=IK2PI;
498 }
499 j1valid[0] = true;
500 if( j1array[1] > IKPI )
501 {
502  j1array[1]-=IK2PI;
503 }
504 else if( j1array[1] < -IKPI )
505 { j1array[1]+=IK2PI;
506 }
507 j1valid[1] = true;
508 for(int ij1 = 0; ij1 < 2; ++ij1)
509 {
510 if( !j1valid[ij1] )
511 {
512  continue;
513 }
514 _ij1[0] = ij1; _ij1[1] = -1;
515 for(int iij1 = ij1+1; iij1 < 2; ++iij1)
516 {
517 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
518 {
519  j1valid[iij1]=false; _ij1[1] = iij1; break;
520 }
521 }
522 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
523 
524 // The remainder of this scope is removed as it does not return a solution.
525 // This is the branch (IKabs(px))+(IKabs(py)), from the kinematics we know,
526 // that j0 is free. So we simply choose 4 values and pass directly to the
527 // rotationfunction (orientation computation is unchanged).
528 _nj0=4;
529 for(int ij0=1; ij0 < _nj0; ++ij0)
530 {
531 j0=(IkReal)(ij0 - 1) * (3.14159265358979) / 2.; // -pi/2, 0, pi/2, pi
532 cj0=IKcos(j0);
533 sj0=IKsin(j0);
534 _ij0[0] = ij0;
535 rotationfunction0(solutions);
536 }
537 
538 }
539 }
540 
541 }
542 
543 }
544 
545 } else
546 {
547 {
548 IkReal j0array[2], cj0array[2], sj0array[2];
549 bool j0valid[2]={false};
550 _nj0 = 2;
551 CheckValue<IkReal> x1691 = IKatan2WithCheck(IkReal(py),IkReal(((-1.0)*px)),IKFAST_ATAN2_MAGTHRESH);
552 if(!x1691.valid){
553 continue;
554 }
555 IkReal x1690=x1691.value;
556 j0array[0]=((-1.0)*x1690);
557 sj0array[0]=IKsin(j0array[0]);
558 cj0array[0]=IKcos(j0array[0]);
559 j0array[1]=((3.14159265358979)+(((-1.0)*x1690)));
560 sj0array[1]=IKsin(j0array[1]);
561 cj0array[1]=IKcos(j0array[1]);
562 if( j0array[0] > IKPI )
563 {
564  j0array[0]-=IK2PI;
565 }
566 else if( j0array[0] < -IKPI )
567 { j0array[0]+=IK2PI;
568 }
569 j0valid[0] = true;
570 if( j0array[1] > IKPI )
571 {
572  j0array[1]-=IK2PI;
573 }
574 else if( j0array[1] < -IKPI )
575 { j0array[1]+=IK2PI;
576 }
577 j0valid[1] = true;
578 for(int ij0 = 0; ij0 < 2; ++ij0)
579 {
580 if( !j0valid[ij0] )
581 {
582  continue;
583 }
584 _ij0[0] = ij0; _ij0[1] = -1;
585 for(int iij0 = ij0+1; iij0 < 2; ++iij0)
586 {
587 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
588 {
589  j0valid[iij0]=false; _ij0[1] = iij0; break;
590 }
591 }
592 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
593 
594 {
595 IkReal j1eval[3];
596 IkReal x1692=((307000.0)*cj2);
597 IkReal x1693=(cj0*px);
598 IkReal x1694=((307000.0)*sj2);
599 IkReal x1695=(py*sj0);
600 j1eval[0]=((-1.00860400186133)+(((-1.0)*cj2)));
601 j1eval[1]=((IKabs(((((-1.0)*pz*x1692))+(((-350000.0)*pz))+((x1693*x1694))+((x1694*x1695)))))+(IKabs(((((-1.0)*x1692*x1693))+(((-1.0)*x1692*x1695))+(((-1.0)*pz*x1694))+(((-350000.0)*x1693))+(((-350000.0)*x1695))))));
602 j1eval[2]=IKsign(((-216749.0)+(((-214900.0)*cj2))));
603 if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 || IKabs(j1eval[2]) < 0.0000010000000000 )
604 {
605 {
606 IkReal j1eval[3];
607 IkReal x1696=(py*sj0);
608 IkReal x1697=((1000.0)*pz);
609 IkReal x1698=(pz*sj2);
610 IkReal x1699=(cj0*px);
611 IkReal x1700=(cj2*x1699);
612 j1eval[0]=((((-1.0)*x1700))+x1698+(((-1.0)*cj2*x1696))+(((-1.1400651465798)*x1696))+(((-1.1400651465798)*x1699)));
613 j1eval[1]=((IKabs(((((-1.0)*x1696*x1697))+(((-1.0)*x1697*x1699))+(((94.249)*cj2*sj2))+(((107.45)*sj2)))))+(IKabs(((-122.5)+(((-94.249)*(cj2*cj2)))+(((-214.9)*cj2))+((pz*x1697))))));
614 j1eval[2]=IKsign(((((-307.0)*x1700))+(((-350.0)*x1699))+(((-350.0)*x1696))+(((-307.0)*cj2*x1696))+(((307.0)*x1698))));
615 if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 || IKabs(j1eval[2]) < 0.0000010000000000 )
616 {
617 {
618 IkReal j1eval[3];
619 IkReal x1701=(cj0*px);
620 IkReal x1702=((1.0)*cj2);
621 IkReal x1703=((7000.0)*pz);
622 IkReal x1704=(py*sj0);
623 IkReal x1705=((2149.0)*cj2);
624 IkReal x1706=(pz*sj2);
625 IkReal x1707=((3070.0)*pp);
626 j1eval[0]=((((-1.1400651465798)*x1704))+(((-1.1400651465798)*x1701))+(((-1.0)*x1702*x1704))+x1706+(((-1.0)*x1701*x1702)));
627 j1eval[1]=((IKabs(((-98.8785)+(((-86.73057)*cj2))+(((-1.0)*cj2*x1707))+(((-3500.0)*pp))+((pz*x1703)))))+(IKabs(((((-1.0)*x1703*x1704))+((sj2*x1707))+(((-1.0)*x1701*x1703))+(((86.73057)*sj2))))));
628 j1eval[2]=IKsign(((((2149.0)*x1706))+(((-2450.0)*x1704))+(((-2450.0)*x1701))+(((-1.0)*x1704*x1705))+(((-1.0)*x1701*x1705))));
629 if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 || IKabs(j1eval[2]) < 0.0000010000000000 )
630 {
631 continue; // no branches [j1]
632 
633 } else
634 {
635 {
636 IkReal j1array[1], cj1array[1], sj1array[1];
637 bool j1valid[1]={false};
638 _nj1 = 1;
639 IkReal x1708=((7000.0)*pz);
640 IkReal x1709=(cj0*px);
641 IkReal x1710=(py*sj0);
642 IkReal x1711=((2149.0)*cj2);
643 IkReal x1712=((3070.0)*pp);
644 CheckValue<IkReal> x1713 = IKatan2WithCheck(IkReal(((-98.8785)+(((-86.73057)*cj2))+(((-3500.0)*pp))+(((-1.0)*cj2*x1712))+((pz*x1708)))),IkReal(((((-1.0)*x1708*x1709))+(((-1.0)*x1708*x1710))+((sj2*x1712))+(((86.73057)*sj2)))),IKFAST_ATAN2_MAGTHRESH);
645 if(!x1713.valid){
646 continue;
647 }
648 CheckValue<IkReal> x1714=IKPowWithIntegerCheck(IKsign(((((-1.0)*x1710*x1711))+(((-1.0)*x1709*x1711))+(((-2450.0)*x1709))+(((-2450.0)*x1710))+(((2149.0)*pz*sj2)))),-1);
649 if(!x1714.valid){
650 continue;
651 }
652 j1array[0]=((-1.5707963267949)+(x1713.value)+(((1.5707963267949)*(x1714.value))));
653 sj1array[0]=IKsin(j1array[0]);
654 cj1array[0]=IKcos(j1array[0]);
655 if( j1array[0] > IKPI )
656 {
657  j1array[0]-=IK2PI;
658 }
659 else if( j1array[0] < -IKPI )
660 { j1array[0]+=IK2PI;
661 }
662 j1valid[0] = true;
663 for(int ij1 = 0; ij1 < 1; ++ij1)
664 {
665 if( !j1valid[ij1] )
666 {
667  continue;
668 }
669 _ij1[0] = ij1; _ij1[1] = -1;
670 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
671 {
672 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
673 {
674  j1valid[iij1]=false; _ij1[1] = iij1; break;
675 }
676 }
677 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
678 {
679 IkReal evalcond[5];
680 IkReal x1715=IKcos(j1);
681 IkReal x1716=IKsin(j1);
682 IkReal x1717=(cj0*px);
683 IkReal x1718=(py*sj0);
684 IkReal x1719=((0.307)*x1715);
685 IkReal x1720=((1.0)*x1718);
686 IkReal x1721=(pz*x1715);
687 IkReal x1722=((0.7)*x1716);
688 IkReal x1723=((0.307)*x1716);
689 evalcond[0]=((((-1.0)*pz))+((cj2*x1719))+(((0.35)*x1715))+((sj2*x1723)));
690 evalcond[1]=((((-1.0)*x1715*x1720))+(((-1.0)*x1715*x1717))+(((-0.307)*sj2))+((pz*x1716)));
691 evalcond[2]=((((-0.35)*x1716))+x1717+x1718+(((-1.0)*cj2*x1723))+((sj2*x1719)));
692 evalcond[3]=((-0.028251)+((x1718*x1722))+((x1717*x1722))+(((-1.0)*pp))+(((0.7)*x1721)));
693 evalcond[4]=((0.35)+(((-1.0)*x1716*x1717))+(((-1.0)*x1721))+(((-1.0)*x1716*x1720))+(((0.307)*cj2)));
694 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
695 {
696 continue;
697 }
698 }
699 
700 rotationfunction0(solutions);
701 }
702 }
703 
704 }
705 
706 }
707 
708 } else
709 {
710 {
711 IkReal j1array[1], cj1array[1], sj1array[1];
712 bool j1valid[1]={false};
713 _nj1 = 1;
714 IkReal x1724=((307.0)*cj2);
715 IkReal x1725=(cj0*px);
716 IkReal x1726=(py*sj0);
717 IkReal x1727=((1000.0)*pz);
718 CheckValue<IkReal> x1728 = IKatan2WithCheck(IkReal(((-122.5)+(((-94.249)*(cj2*cj2)))+((pz*x1727))+(((-214.9)*cj2)))),IkReal(((((-1.0)*x1726*x1727))+(((94.249)*cj2*sj2))+(((107.45)*sj2))+(((-1.0)*x1725*x1727)))),IKFAST_ATAN2_MAGTHRESH);
719 if(!x1728.valid){
720 continue;
721 }
722 CheckValue<IkReal> x1729=IKPowWithIntegerCheck(IKsign(((((-350.0)*x1726))+(((-350.0)*x1725))+(((307.0)*pz*sj2))+(((-1.0)*x1724*x1725))+(((-1.0)*x1724*x1726)))),-1);
723 if(!x1729.valid){
724 continue;
725 }
726 j1array[0]=((-1.5707963267949)+(x1728.value)+(((1.5707963267949)*(x1729.value))));
727 sj1array[0]=IKsin(j1array[0]);
728 cj1array[0]=IKcos(j1array[0]);
729 if( j1array[0] > IKPI )
730 {
731  j1array[0]-=IK2PI;
732 }
733 else if( j1array[0] < -IKPI )
734 { j1array[0]+=IK2PI;
735 }
736 j1valid[0] = true;
737 for(int ij1 = 0; ij1 < 1; ++ij1)
738 {
739 if( !j1valid[ij1] )
740 {
741  continue;
742 }
743 _ij1[0] = ij1; _ij1[1] = -1;
744 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
745 {
746 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
747 {
748  j1valid[iij1]=false; _ij1[1] = iij1; break;
749 }
750 }
751 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
752 {
753 IkReal evalcond[5];
754 IkReal x1730=IKcos(j1);
755 IkReal x1731=IKsin(j1);
756 IkReal x1732=(cj0*px);
757 IkReal x1733=(py*sj0);
758 IkReal x1734=((0.307)*x1730);
759 IkReal x1735=((1.0)*x1733);
760 IkReal x1736=(pz*x1730);
761 IkReal x1737=((0.7)*x1731);
762 IkReal x1738=((0.307)*x1731);
763 evalcond[0]=(((cj2*x1734))+(((0.35)*x1730))+(((-1.0)*pz))+((sj2*x1738)));
764 evalcond[1]=(((pz*x1731))+(((-0.307)*sj2))+(((-1.0)*x1730*x1735))+(((-1.0)*x1730*x1732)));
765 evalcond[2]=(x1733+x1732+(((-1.0)*cj2*x1738))+(((-0.35)*x1731))+((sj2*x1734)));
766 evalcond[3]=((-0.028251)+(((-1.0)*pp))+(((0.7)*x1736))+((x1732*x1737))+((x1733*x1737)));
767 evalcond[4]=((0.35)+(((-1.0)*x1731*x1735))+(((-1.0)*x1731*x1732))+(((-1.0)*x1736))+(((0.307)*cj2)));
768 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
769 {
770 continue;
771 }
772 }
773 
774 rotationfunction0(solutions);
775 }
776 }
777 
778 }
779 
780 }
781 
782 } else
783 {
784 {
785 IkReal j1array[1], cj1array[1], sj1array[1];
786 bool j1valid[1]={false};
787 _nj1 = 1;
788 IkReal x1739=((307000.0)*cj2);
789 IkReal x1740=(cj0*px);
790 IkReal x1741=((307000.0)*sj2);
791 IkReal x1742=(py*sj0);
792 CheckValue<IkReal> x1743=IKPowWithIntegerCheck(IKsign(((-216749.0)+(((-214900.0)*cj2)))),-1);
793 if(!x1743.valid){
794 continue;
795 }
796 CheckValue<IkReal> x1744 = IKatan2WithCheck(IkReal(((((-350000.0)*x1742))+(((-350000.0)*x1740))+(((-1.0)*x1739*x1740))+(((-1.0)*x1739*x1742))+(((-1.0)*pz*x1741)))),IkReal(((((-1.0)*pz*x1739))+(((-350000.0)*pz))+((x1740*x1741))+((x1741*x1742)))),IKFAST_ATAN2_MAGTHRESH);
797 if(!x1744.valid){
798 continue;
799 }
800 j1array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1743.value)))+(x1744.value));
801 sj1array[0]=IKsin(j1array[0]);
802 cj1array[0]=IKcos(j1array[0]);
803 if( j1array[0] > IKPI )
804 {
805  j1array[0]-=IK2PI;
806 }
807 else if( j1array[0] < -IKPI )
808 { j1array[0]+=IK2PI;
809 }
810 j1valid[0] = true;
811 for(int ij1 = 0; ij1 < 1; ++ij1)
812 {
813 if( !j1valid[ij1] )
814 {
815  continue;
816 }
817 _ij1[0] = ij1; _ij1[1] = -1;
818 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
819 {
820 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
821 {
822  j1valid[iij1]=false; _ij1[1] = iij1; break;
823 }
824 }
825 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
826 {
827 IkReal evalcond[5];
828 IkReal x1745=IKcos(j1);
829 IkReal x1746=IKsin(j1);
830 IkReal x1747=(cj0*px);
831 IkReal x1748=(py*sj0);
832 IkReal x1749=((0.307)*x1745);
833 IkReal x1750=((1.0)*x1748);
834 IkReal x1751=(pz*x1745);
835 IkReal x1752=((0.7)*x1746);
836 IkReal x1753=((0.307)*x1746);
837 evalcond[0]=((((0.35)*x1745))+((cj2*x1749))+(((-1.0)*pz))+((sj2*x1753)));
838 evalcond[1]=(((pz*x1746))+(((-0.307)*sj2))+(((-1.0)*x1745*x1750))+(((-1.0)*x1745*x1747)));
839 evalcond[2]=(x1748+x1747+(((-1.0)*cj2*x1753))+((sj2*x1749))+(((-0.35)*x1746)));
840 evalcond[3]=((-0.028251)+((x1747*x1752))+(((-1.0)*pp))+((x1748*x1752))+(((0.7)*x1751)));
841 evalcond[4]=((0.35)+(((-1.0)*x1746*x1747))+(((-1.0)*x1746*x1750))+(((-1.0)*x1751))+(((0.307)*cj2)));
842 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
843 {
844 continue;
845 }
846 }
847 
848 rotationfunction0(solutions);
849 }
850 }
851 
852 }
853 
854 }
855 }
856 }
857 
858 }
859 
860 }
861 }
862 }
863 }
864 return solutions.GetNumSolutions()>0;
865 }
867 for(int rotationiter = 0; rotationiter < 1; ++rotationiter) {
868 IkReal x70=(r11*sj0);
869 IkReal x71=(cj0*r02);
870 IkReal x72=(r10*sj0);
871 IkReal x73=((1.0)*sj0);
872 IkReal x74=(cj2*sj1);
873 IkReal x75=(cj1*sj2);
874 IkReal x76=(r12*sj0);
875 IkReal x77=(((sj1*sj2))+((cj1*cj2)));
876 IkReal x78=(x75+(((-1.0)*x74)));
877 IkReal x79=(x74+(((-1.0)*x75)));
878 IkReal x80=(sj0*x79);
879 IkReal x81=(cj0*x79);
880 IkReal x82=(cj0*x77);
881 new_r00=(((r00*x82))+((x72*x77))+((r20*x78)));
882 new_r01=(((r21*x78))+((r01*x82))+((x70*x77)));
883 new_r02=(((r22*x78))+((x76*x77))+((x71*x77)));
884 new_r10=((((-1.0)*r00*x73))+((cj0*r10)));
885 new_r11=((((-1.0)*r01*x73))+((cj0*r11)));
886 new_r12=((((-1.0)*r02*x73))+((cj0*r12)));
887 new_r20=(((r00*x81))+((x72*x79))+((r20*x77)));
888 new_r21=(((r21*x77))+((r01*x81))+((x70*x79)));
889 new_r22=(((r22*x77))+((x76*x79))+((x71*x79)));
890 {
891 IkReal j4array[2], cj4array[2], sj4array[2];
892 bool j4valid[2]={false};
893 _nj4 = 2;
894 cj4array[0]=new_r22;
895 if( cj4array[0] >= -1-IKFAST_SINCOS_THRESH && cj4array[0] <= 1+IKFAST_SINCOS_THRESH )
896 {
897  j4valid[0] = j4valid[1] = true;
898  j4array[0] = IKacos(cj4array[0]);
899  sj4array[0] = IKsin(j4array[0]);
900  cj4array[1] = cj4array[0];
901  j4array[1] = -j4array[0];
902  sj4array[1] = -sj4array[0];
903 }
904 else if( isnan(cj4array[0]) )
905 {
906  // probably any value will work
907  j4valid[0] = true;
908  cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0;
909 }
910 for(int ij4 = 0; ij4 < 2; ++ij4)
911 {
912 if( !j4valid[ij4] )
913 {
914  continue;
915 }
916 _ij4[0] = ij4; _ij4[1] = -1;
917 for(int iij4 = ij4+1; iij4 < 2; ++iij4)
918 {
919 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
920 {
921  j4valid[iij4]=false; _ij4[1] = iij4; break;
922 }
923 }
924 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
925 
926 {
927 IkReal j5eval[3];
928 j5eval[0]=sj4;
929 j5eval[1]=IKsign(sj4);
930 j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21)));
931 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
932 {
933 {
934 IkReal j3eval[3];
935 j3eval[0]=sj4;
936 j3eval[1]=IKsign(sj4);
937 j3eval[2]=((IKabs(new_r12))+(IKabs(new_r02)));
938 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
939 {
940 {
941 IkReal j3eval[2];
942 j3eval[0]=new_r12;
943 j3eval[1]=sj4;
944 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
945 {
946 {
947 IkReal evalcond[5];
948 bool bgotonextstatement = true;
949 do
950 {
951 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959)));
952 evalcond[1]=new_r02;
953 evalcond[2]=new_r12;
954 evalcond[3]=new_r21;
955 evalcond[4]=new_r20;
956 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
957 {
958 bgotonextstatement=false;
959 IkReal j5mul = 1;
960 j5=0;
961 j3mul=-1.0;
962 if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(new_r00)-1) <= IKFAST_SINCOS_THRESH )
963  continue;
964 j3=IKatan2(((-1.0)*new_r01), new_r00);
965 {
966 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
967 vinfos[0].jointtype = 1;
968 vinfos[0].foffset = j0;
969 vinfos[0].indices[0] = _ij0[0];
970 vinfos[0].indices[1] = _ij0[1];
971 vinfos[0].maxsolutions = _nj0;
972 vinfos[1].jointtype = 1;
973 vinfos[1].foffset = j1;
974 vinfos[1].indices[0] = _ij1[0];
975 vinfos[1].indices[1] = _ij1[1];
976 vinfos[1].maxsolutions = _nj1;
977 vinfos[2].jointtype = 1;
978 vinfos[2].foffset = j2;
979 vinfos[2].indices[0] = _ij2[0];
980 vinfos[2].indices[1] = _ij2[1];
981 vinfos[2].maxsolutions = _nj2;
982 vinfos[3].jointtype = 1;
983 vinfos[3].foffset = j3;
984 vinfos[3].fmul = j3mul;
985 vinfos[3].freeind = 0;
986 vinfos[3].maxsolutions = 0;
987 vinfos[4].jointtype = 1;
988 vinfos[4].foffset = j4;
989 vinfos[4].indices[0] = _ij4[0];
990 vinfos[4].indices[1] = _ij4[1];
991 vinfos[4].maxsolutions = _nj4;
992 vinfos[5].jointtype = 1;
993 vinfos[5].foffset = j5;
994 vinfos[5].fmul = j5mul;
995 vinfos[5].freeind = 0;
996 vinfos[5].maxsolutions = 0;
997 std::vector<int> vfree(1);
998 vfree[0] = 5;
999 solutions.AddSolution(vinfos,vfree);
1000 }
1001 
1002 }
1003 } while(0);
1004 if( bgotonextstatement )
1005 {
1006 bool bgotonextstatement = true;
1007 do
1008 {
1009 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959)));
1010 evalcond[1]=new_r02;
1011 evalcond[2]=new_r12;
1012 evalcond[3]=new_r21;
1013 evalcond[4]=new_r20;
1014 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
1015 {
1016 bgotonextstatement=false;
1017 IkReal j5mul = 1;
1018 j5=0;
1019 j3mul=1.0;
1020 if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(((-1.0)*new_r00))-1) <= IKFAST_SINCOS_THRESH )
1021  continue;
1022 j3=IKatan2(((-1.0)*new_r01), ((-1.0)*new_r00));
1023 {
1024 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1025 vinfos[0].jointtype = 1;
1026 vinfos[0].foffset = j0;
1027 vinfos[0].indices[0] = _ij0[0];
1028 vinfos[0].indices[1] = _ij0[1];
1029 vinfos[0].maxsolutions = _nj0;
1030 vinfos[1].jointtype = 1;
1031 vinfos[1].foffset = j1;
1032 vinfos[1].indices[0] = _ij1[0];
1033 vinfos[1].indices[1] = _ij1[1];
1034 vinfos[1].maxsolutions = _nj1;
1035 vinfos[2].jointtype = 1;
1036 vinfos[2].foffset = j2;
1037 vinfos[2].indices[0] = _ij2[0];
1038 vinfos[2].indices[1] = _ij2[1];
1039 vinfos[2].maxsolutions = _nj2;
1040 vinfos[3].jointtype = 1;
1041 vinfos[3].foffset = j3;
1042 vinfos[3].fmul = j3mul;
1043 vinfos[3].freeind = 0;
1044 vinfos[3].maxsolutions = 0;
1045 vinfos[4].jointtype = 1;
1046 vinfos[4].foffset = j4;
1047 vinfos[4].indices[0] = _ij4[0];
1048 vinfos[4].indices[1] = _ij4[1];
1049 vinfos[4].maxsolutions = _nj4;
1050 vinfos[5].jointtype = 1;
1051 vinfos[5].foffset = j5;
1052 vinfos[5].fmul = j5mul;
1053 vinfos[5].freeind = 0;
1054 vinfos[5].maxsolutions = 0;
1055 std::vector<int> vfree(1);
1056 vfree[0] = 5;
1057 solutions.AddSolution(vinfos,vfree);
1058 }
1059 
1060 }
1061 } while(0);
1062 if( bgotonextstatement )
1063 {
1064 bool bgotonextstatement = true;
1065 do
1066 {
1067 evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21)));
1068 if( IKabs(evalcond[0]) < 0.0000050000000000 )
1069 {
1070 bgotonextstatement=false;
1071 {
1072 IkReal j3eval[1];
1073 new_r21=0;
1074 new_r20=0;
1075 new_r02=0;
1076 new_r12=0;
1077 IkReal x83=new_r22*new_r22;
1078 IkReal x84=((16.0)*new_r10);
1079 IkReal x85=((16.0)*new_r01);
1080 IkReal x86=((16.0)*new_r22);
1081 IkReal x87=((8.0)*new_r11);
1082 IkReal x88=((8.0)*new_r00);
1083 IkReal x89=(x83*x84);
1084 IkReal x90=(x83*x85);
1085 j3eval[0]=((IKabs((x89+(((-1.0)*x84)))))+(IKabs((((new_r22*x88))+(((-1.0)*x83*x87)))))+(IKabs(((((16.0)*new_r00))+((new_r11*x86))+(((-32.0)*new_r00*x83)))))+(IKabs((x85+(((-1.0)*x90)))))+(IKabs((((new_r22*x87))+(((-1.0)*x88)))))+(IKabs(((((16.0)*new_r11*x83))+((new_r00*x86))+(((-32.0)*new_r11)))))+(IKabs((x90+(((-1.0)*x85)))))+(IKabs((x84+(((-1.0)*x89))))));
1086 if( IKabs(j3eval[0]) < 0.0000000100000000 )
1087 {
1088 continue; // no branches [j3, j5]
1089 
1090 } else
1091 {
1092 IkReal op[4+1], zeror[4];
1093 int numroots;
1094 IkReal j3evalpoly[1];
1095 IkReal x91=new_r22*new_r22;
1096 IkReal x92=((16.0)*new_r10);
1097 IkReal x93=(new_r11*new_r22);
1098 IkReal x94=(x91*x92);
1099 IkReal x95=((((8.0)*x93))+(((-8.0)*new_r00)));
1100 op[0]=x95;
1101 op[1]=(x92+(((-1.0)*x94)));
1102 op[2]=((((16.0)*x93))+(((16.0)*new_r00))+(((-32.0)*new_r00*x91)));
1103 op[3]=(x94+(((-1.0)*x92)));
1104 op[4]=x95;
1105 polyroots4(op,zeror,numroots);
1106 IkReal j3array[4], cj3array[4], sj3array[4], tempj3array[1];
1107 int numsolutions = 0;
1108 for(int ij3 = 0; ij3 < numroots; ++ij3)
1109 {
1110 IkReal htj3 = zeror[ij3];
1111 tempj3array[0]=((2.0)*(atan(htj3)));
1112 for(int kj3 = 0; kj3 < 1; ++kj3)
1113 {
1114 j3array[numsolutions] = tempj3array[kj3];
1115 if( j3array[numsolutions] > IKPI )
1116 {
1117  j3array[numsolutions]-=IK2PI;
1118 }
1119 else if( j3array[numsolutions] < -IKPI )
1120 {
1121  j3array[numsolutions]+=IK2PI;
1122 }
1123 sj3array[numsolutions] = IKsin(j3array[numsolutions]);
1124 cj3array[numsolutions] = IKcos(j3array[numsolutions]);
1125 numsolutions++;
1126 }
1127 }
1128 bool j3valid[4]={true,true,true,true};
1129 _nj3 = 4;
1130 for(int ij3 = 0; ij3 < numsolutions; ++ij3)
1131  {
1132 if( !j3valid[ij3] )
1133 {
1134  continue;
1135 }
1136  j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1137 htj3 = IKtan(j3/2);
1138 
1139 IkReal x96=((16.0)*new_r01);
1140 IkReal x97=new_r22*new_r22;
1141 IkReal x98=(new_r00*new_r22);
1142 IkReal x99=((8.0)*x98);
1143 IkReal x100=(new_r11*x97);
1144 IkReal x101=(x96*x97);
1145 IkReal x102=((8.0)*x100);
1146 j3evalpoly[0]=((((-1.0)*x102))+(((htj3*htj3*htj3)*(((((-1.0)*x101))+x96))))+(((htj3*htj3*htj3*htj3)*(((((-1.0)*x102))+x99))))+((htj3*((x101+(((-1.0)*x96))))))+(((htj3*htj3)*(((((16.0)*x98))+(((16.0)*x100))+(((-32.0)*new_r11))))))+x99);
1147 if( IKabs(j3evalpoly[0]) > 0.0000001000000000 )
1148 {
1149  continue;
1150 }
1151 _ij3[0] = ij3; _ij3[1] = -1;
1152 for(int iij3 = ij3+1; iij3 < numsolutions; ++iij3)
1153 {
1154 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1155 {
1156  j3valid[iij3]=false; _ij3[1] = iij3; break;
1157 }
1158 }
1159 {
1160 IkReal j5eval[3];
1161 new_r21=0;
1162 new_r20=0;
1163 new_r02=0;
1164 new_r12=0;
1165 IkReal x103=cj3*cj3;
1166 IkReal x104=(cj3*new_r22);
1167 IkReal x105=((-1.0)+x103+(((-1.0)*x103*(new_r22*new_r22))));
1168 j5eval[0]=x105;
1169 j5eval[1]=((IKabs((((new_r01*sj3))+(((-1.0)*new_r00*x104)))))+(IKabs((((new_r00*sj3))+((new_r01*x104))))));
1170 j5eval[2]=IKsign(x105);
1171 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1172 {
1173 {
1174 IkReal j5eval[1];
1175 new_r21=0;
1176 new_r20=0;
1177 new_r02=0;
1178 new_r12=0;
1179 j5eval[0]=new_r22;
1180 if( IKabs(j5eval[0]) < 0.0000010000000000 )
1181 {
1182 {
1183 IkReal j5eval[1];
1184 new_r21=0;
1185 new_r20=0;
1186 new_r02=0;
1187 new_r12=0;
1188 j5eval[0]=sj3;
1189 if( IKabs(j5eval[0]) < 0.0000010000000000 )
1190 {
1191 {
1192 IkReal evalcond[1];
1193 bool bgotonextstatement = true;
1194 do
1195 {
1196 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j3))), 6.28318530717959)));
1197 if( IKabs(evalcond[0]) < 0.0000050000000000 )
1198 {
1199 bgotonextstatement=false;
1200 {
1201 IkReal j5array[1], cj5array[1], sj5array[1];
1202 bool j5valid[1]={false};
1203 _nj5 = 1;
1204 if( IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r10)+IKsqr(new_r11)-1) <= IKFAST_SINCOS_THRESH )
1205  continue;
1206 j5array[0]=IKatan2(new_r10, new_r11);
1207 sj5array[0]=IKsin(j5array[0]);
1208 cj5array[0]=IKcos(j5array[0]);
1209 if( j5array[0] > IKPI )
1210 {
1211  j5array[0]-=IK2PI;
1212 }
1213 else if( j5array[0] < -IKPI )
1214 { j5array[0]+=IK2PI;
1215 }
1216 j5valid[0] = true;
1217 for(int ij5 = 0; ij5 < 1; ++ij5)
1218 {
1219 if( !j5valid[ij5] )
1220 {
1221  continue;
1222 }
1223 _ij5[0] = ij5; _ij5[1] = -1;
1224 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1225 {
1226 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1227 {
1228  j5valid[iij5]=false; _ij5[1] = iij5; break;
1229 }
1230 }
1231 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1232 {
1233 IkReal evalcond[4];
1234 IkReal x106=IKsin(j5);
1235 IkReal x107=IKcos(j5);
1236 evalcond[0]=x107;
1237 evalcond[1]=((-1.0)*x106);
1238 evalcond[2]=(x106+(((-1.0)*new_r10)));
1239 evalcond[3]=(x107+(((-1.0)*new_r11)));
1240 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
1241 {
1242 continue;
1243 }
1244 }
1245 
1246 {
1247 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1248 vinfos[0].jointtype = 1;
1249 vinfos[0].foffset = j0;
1250 vinfos[0].indices[0] = _ij0[0];
1251 vinfos[0].indices[1] = _ij0[1];
1252 vinfos[0].maxsolutions = _nj0;
1253 vinfos[1].jointtype = 1;
1254 vinfos[1].foffset = j1;
1255 vinfos[1].indices[0] = _ij1[0];
1256 vinfos[1].indices[1] = _ij1[1];
1257 vinfos[1].maxsolutions = _nj1;
1258 vinfos[2].jointtype = 1;
1259 vinfos[2].foffset = j2;
1260 vinfos[2].indices[0] = _ij2[0];
1261 vinfos[2].indices[1] = _ij2[1];
1262 vinfos[2].maxsolutions = _nj2;
1263 vinfos[3].jointtype = 1;
1264 vinfos[3].foffset = j3;
1265 vinfos[3].indices[0] = _ij3[0];
1266 vinfos[3].indices[1] = _ij3[1];
1267 vinfos[3].maxsolutions = _nj3;
1268 vinfos[4].jointtype = 1;
1269 vinfos[4].foffset = j4;
1270 vinfos[4].indices[0] = _ij4[0];
1271 vinfos[4].indices[1] = _ij4[1];
1272 vinfos[4].maxsolutions = _nj4;
1273 vinfos[5].jointtype = 1;
1274 vinfos[5].foffset = j5;
1275 vinfos[5].indices[0] = _ij5[0];
1276 vinfos[5].indices[1] = _ij5[1];
1277 vinfos[5].maxsolutions = _nj5;
1278 std::vector<int> vfree(0);
1279 solutions.AddSolution(vinfos,vfree);
1280 }
1281 }
1282 }
1283 
1284 }
1285 } while(0);
1286 if( bgotonextstatement )
1287 {
1288 bool bgotonextstatement = true;
1289 do
1290 {
1291 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j3)))), 6.28318530717959)));
1292 if( IKabs(evalcond[0]) < 0.0000050000000000 )
1293 {
1294 bgotonextstatement=false;
1295 {
1296 IkReal j5array[1], cj5array[1], sj5array[1];
1297 bool j5valid[1]={false};
1298 _nj5 = 1;
1299 if( IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r10))+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH )
1300  continue;
1301 j5array[0]=IKatan2(((-1.0)*new_r10), ((-1.0)*new_r11));
1302 sj5array[0]=IKsin(j5array[0]);
1303 cj5array[0]=IKcos(j5array[0]);
1304 if( j5array[0] > IKPI )
1305 {
1306  j5array[0]-=IK2PI;
1307 }
1308 else if( j5array[0] < -IKPI )
1309 { j5array[0]+=IK2PI;
1310 }
1311 j5valid[0] = true;
1312 for(int ij5 = 0; ij5 < 1; ++ij5)
1313 {
1314 if( !j5valid[ij5] )
1315 {
1316  continue;
1317 }
1318 _ij5[0] = ij5; _ij5[1] = -1;
1319 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1320 {
1321 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1322 {
1323  j5valid[iij5]=false; _ij5[1] = iij5; break;
1324 }
1325 }
1326 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1327 {
1328 IkReal evalcond[4];
1329 IkReal x108=IKcos(j5);
1330 IkReal x109=IKsin(j5);
1331 evalcond[0]=x108;
1332 evalcond[1]=(x109+new_r10);
1333 evalcond[2]=(x108+new_r11);
1334 evalcond[3]=((-1.0)*x109);
1335 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
1336 {
1337 continue;
1338 }
1339 }
1340 
1341 {
1342 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1343 vinfos[0].jointtype = 1;
1344 vinfos[0].foffset = j0;
1345 vinfos[0].indices[0] = _ij0[0];
1346 vinfos[0].indices[1] = _ij0[1];
1347 vinfos[0].maxsolutions = _nj0;
1348 vinfos[1].jointtype = 1;
1349 vinfos[1].foffset = j1;
1350 vinfos[1].indices[0] = _ij1[0];
1351 vinfos[1].indices[1] = _ij1[1];
1352 vinfos[1].maxsolutions = _nj1;
1353 vinfos[2].jointtype = 1;
1354 vinfos[2].foffset = j2;
1355 vinfos[2].indices[0] = _ij2[0];
1356 vinfos[2].indices[1] = _ij2[1];
1357 vinfos[2].maxsolutions = _nj2;
1358 vinfos[3].jointtype = 1;
1359 vinfos[3].foffset = j3;
1360 vinfos[3].indices[0] = _ij3[0];
1361 vinfos[3].indices[1] = _ij3[1];
1362 vinfos[3].maxsolutions = _nj3;
1363 vinfos[4].jointtype = 1;
1364 vinfos[4].foffset = j4;
1365 vinfos[4].indices[0] = _ij4[0];
1366 vinfos[4].indices[1] = _ij4[1];
1367 vinfos[4].maxsolutions = _nj4;
1368 vinfos[5].jointtype = 1;
1369 vinfos[5].foffset = j5;
1370 vinfos[5].indices[0] = _ij5[0];
1371 vinfos[5].indices[1] = _ij5[1];
1372 vinfos[5].maxsolutions = _nj5;
1373 std::vector<int> vfree(0);
1374 solutions.AddSolution(vinfos,vfree);
1375 }
1376 }
1377 }
1378 
1379 }
1380 } while(0);
1381 if( bgotonextstatement )
1382 {
1383 bool bgotonextstatement = true;
1384 do
1385 {
1386 CheckValue<IkReal> x110=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
1387 if(!x110.valid){
1388 continue;
1389 }
1390 if((x110.value) < -0.00001)
1391 continue;
1392 IkReal gconst18=((-1.0)*(IKsqrt(x110.value)));
1393 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst18)))))), 6.28318530717959)));
1394 if( IKabs(evalcond[0]) < 0.0000050000000000 )
1395 {
1396 bgotonextstatement=false;
1397 {
1398 IkReal j5eval[1];
1399 new_r21=0;
1400 new_r20=0;
1401 new_r02=0;
1402 new_r12=0;
1403 if((((1.0)+(((-1.0)*(gconst18*gconst18))))) < -0.00001)
1404 continue;
1405 sj3=IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18)))));
1406 cj3=gconst18;
1407 if( (gconst18) < -1-IKFAST_SINCOS_THRESH || (gconst18) > 1+IKFAST_SINCOS_THRESH )
1408  continue;
1409 j3=IKacos(gconst18);
1410 CheckValue<IkReal> x111=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
1411 if(!x111.valid){
1412 continue;
1413 }
1414 if((x111.value) < -0.00001)
1415 continue;
1416 IkReal gconst18=((-1.0)*(IKsqrt(x111.value)));
1417 j5eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
1418 if( IKabs(j5eval[0]) < 0.0000010000000000 )
1419 {
1420 {
1421 IkReal j5array[1], cj5array[1], sj5array[1];
1422 bool j5valid[1]={false};
1423 _nj5 = 1;
1424 if((((1.0)+(((-1.0)*(gconst18*gconst18))))) < -0.00001)
1425 continue;
1426 CheckValue<IkReal> x112=IKPowWithIntegerCheck(gconst18,-1);
1427 if(!x112.valid){
1428 continue;
1429 }
1430 if( IKabs((((gconst18*new_r10))+(((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18)))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r11*(x112.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((gconst18*new_r10))+(((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18))))))))))+IKsqr((new_r11*(x112.value)))-1) <= IKFAST_SINCOS_THRESH )
1431  continue;
1432 j5array[0]=IKatan2((((gconst18*new_r10))+(((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18))))))))), (new_r11*(x112.value)));
1433 sj5array[0]=IKsin(j5array[0]);
1434 cj5array[0]=IKcos(j5array[0]);
1435 if( j5array[0] > IKPI )
1436 {
1437  j5array[0]-=IK2PI;
1438 }
1439 else if( j5array[0] < -IKPI )
1440 { j5array[0]+=IK2PI;
1441 }
1442 j5valid[0] = true;
1443 for(int ij5 = 0; ij5 < 1; ++ij5)
1444 {
1445 if( !j5valid[ij5] )
1446 {
1447  continue;
1448 }
1449 _ij5[0] = ij5; _ij5[1] = -1;
1450 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1451 {
1452 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1453 {
1454  j5valid[iij5]=false; _ij5[1] = iij5; break;
1455 }
1456 }
1457 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1458 {
1459 IkReal evalcond[8];
1460 IkReal x113=IKcos(j5);
1461 IkReal x114=IKsin(j5);
1462 IkReal x115=((1.0)*gconst18);
1463 if((((1.0)+(((-1.0)*gconst18*x115)))) < -0.00001)
1464 continue;
1465 IkReal x116=IKsqrt(((1.0)+(((-1.0)*gconst18*x115))));
1466 evalcond[0]=x113;
1467 evalcond[1]=((-1.0)*x114);
1468 evalcond[2]=((((-1.0)*x113*x115))+new_r11);
1469 evalcond[3]=((((-1.0)*x114*x115))+new_r10);
1470 evalcond[4]=(((x113*x116))+new_r01);
1471 evalcond[5]=(((x114*x116))+new_r00);
1472 evalcond[6]=((((-1.0)*new_r10*x115))+x114+((new_r00*x116)));
1473 evalcond[7]=((((-1.0)*new_r11*x115))+x113+((new_r01*x116)));
1474 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
1475 {
1476 continue;
1477 }
1478 }
1479 
1480 {
1481 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1482 vinfos[0].jointtype = 1;
1483 vinfos[0].foffset = j0;
1484 vinfos[0].indices[0] = _ij0[0];
1485 vinfos[0].indices[1] = _ij0[1];
1486 vinfos[0].maxsolutions = _nj0;
1487 vinfos[1].jointtype = 1;
1488 vinfos[1].foffset = j1;
1489 vinfos[1].indices[0] = _ij1[0];
1490 vinfos[1].indices[1] = _ij1[1];
1491 vinfos[1].maxsolutions = _nj1;
1492 vinfos[2].jointtype = 1;
1493 vinfos[2].foffset = j2;
1494 vinfos[2].indices[0] = _ij2[0];
1495 vinfos[2].indices[1] = _ij2[1];
1496 vinfos[2].maxsolutions = _nj2;
1497 vinfos[3].jointtype = 1;
1498 vinfos[3].foffset = j3;
1499 vinfos[3].indices[0] = _ij3[0];
1500 vinfos[3].indices[1] = _ij3[1];
1501 vinfos[3].maxsolutions = _nj3;
1502 vinfos[4].jointtype = 1;
1503 vinfos[4].foffset = j4;
1504 vinfos[4].indices[0] = _ij4[0];
1505 vinfos[4].indices[1] = _ij4[1];
1506 vinfos[4].maxsolutions = _nj4;
1507 vinfos[5].jointtype = 1;
1508 vinfos[5].foffset = j5;
1509 vinfos[5].indices[0] = _ij5[0];
1510 vinfos[5].indices[1] = _ij5[1];
1511 vinfos[5].maxsolutions = _nj5;
1512 std::vector<int> vfree(0);
1513 solutions.AddSolution(vinfos,vfree);
1514 }
1515 }
1516 }
1517 
1518 } else
1519 {
1520 {
1521 IkReal j5array[1], cj5array[1], sj5array[1];
1522 bool j5valid[1]={false};
1523 _nj5 = 1;
1525 if(!x117.valid){
1526 continue;
1527 }
1528 CheckValue<IkReal> x118 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
1529 if(!x118.valid){
1530 continue;
1531 }
1532 j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x117.value)))+(x118.value));
1533 sj5array[0]=IKsin(j5array[0]);
1534 cj5array[0]=IKcos(j5array[0]);
1535 if( j5array[0] > IKPI )
1536 {
1537  j5array[0]-=IK2PI;
1538 }
1539 else if( j5array[0] < -IKPI )
1540 { j5array[0]+=IK2PI;
1541 }
1542 j5valid[0] = true;
1543 for(int ij5 = 0; ij5 < 1; ++ij5)
1544 {
1545 if( !j5valid[ij5] )
1546 {
1547  continue;
1548 }
1549 _ij5[0] = ij5; _ij5[1] = -1;
1550 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1551 {
1552 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1553 {
1554  j5valid[iij5]=false; _ij5[1] = iij5; break;
1555 }
1556 }
1557 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1558 {
1559 IkReal evalcond[8];
1560 IkReal x119=IKcos(j5);
1561 IkReal x120=IKsin(j5);
1562 IkReal x121=((1.0)*gconst18);
1563 if((((1.0)+(((-1.0)*gconst18*x121)))) < -0.00001)
1564 continue;
1565 IkReal x122=IKsqrt(((1.0)+(((-1.0)*gconst18*x121))));
1566 evalcond[0]=x119;
1567 evalcond[1]=((-1.0)*x120);
1568 evalcond[2]=((((-1.0)*x119*x121))+new_r11);
1569 evalcond[3]=((((-1.0)*x120*x121))+new_r10);
1570 evalcond[4]=(new_r01+((x119*x122)));
1571 evalcond[5]=(((x120*x122))+new_r00);
1572 evalcond[6]=((((-1.0)*new_r10*x121))+((new_r00*x122))+x120);
1573 evalcond[7]=(((new_r01*x122))+x119+(((-1.0)*new_r11*x121)));
1574 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
1575 {
1576 continue;
1577 }
1578 }
1579 
1580 {
1581 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1582 vinfos[0].jointtype = 1;
1583 vinfos[0].foffset = j0;
1584 vinfos[0].indices[0] = _ij0[0];
1585 vinfos[0].indices[1] = _ij0[1];
1586 vinfos[0].maxsolutions = _nj0;
1587 vinfos[1].jointtype = 1;
1588 vinfos[1].foffset = j1;
1589 vinfos[1].indices[0] = _ij1[0];
1590 vinfos[1].indices[1] = _ij1[1];
1591 vinfos[1].maxsolutions = _nj1;
1592 vinfos[2].jointtype = 1;
1593 vinfos[2].foffset = j2;
1594 vinfos[2].indices[0] = _ij2[0];
1595 vinfos[2].indices[1] = _ij2[1];
1596 vinfos[2].maxsolutions = _nj2;
1597 vinfos[3].jointtype = 1;
1598 vinfos[3].foffset = j3;
1599 vinfos[3].indices[0] = _ij3[0];
1600 vinfos[3].indices[1] = _ij3[1];
1601 vinfos[3].maxsolutions = _nj3;
1602 vinfos[4].jointtype = 1;
1603 vinfos[4].foffset = j4;
1604 vinfos[4].indices[0] = _ij4[0];
1605 vinfos[4].indices[1] = _ij4[1];
1606 vinfos[4].maxsolutions = _nj4;
1607 vinfos[5].jointtype = 1;
1608 vinfos[5].foffset = j5;
1609 vinfos[5].indices[0] = _ij5[0];
1610 vinfos[5].indices[1] = _ij5[1];
1611 vinfos[5].maxsolutions = _nj5;
1612 std::vector<int> vfree(0);
1613 solutions.AddSolution(vinfos,vfree);
1614 }
1615 }
1616 }
1617 
1618 }
1619 
1620 }
1621 
1622 }
1623 } while(0);
1624 if( bgotonextstatement )
1625 {
1626 bool bgotonextstatement = true;
1627 do
1628 {
1629 CheckValue<IkReal> x123=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
1630 if(!x123.valid){
1631 continue;
1632 }
1633 if((x123.value) < -0.00001)
1634 continue;
1635 IkReal gconst18=((-1.0)*(IKsqrt(x123.value)));
1636 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst18)))))), 6.28318530717959)));
1637 if( IKabs(evalcond[0]) < 0.0000050000000000 )
1638 {
1639 bgotonextstatement=false;
1640 {
1641 IkReal j5eval[1];
1642 new_r21=0;
1643 new_r20=0;
1644 new_r02=0;
1645 new_r12=0;
1646 if((((1.0)+(((-1.0)*(gconst18*gconst18))))) < -0.00001)
1647 continue;
1648 sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18)))))));
1649 cj3=gconst18;
1650 if( (gconst18) < -1-IKFAST_SINCOS_THRESH || (gconst18) > 1+IKFAST_SINCOS_THRESH )
1651  continue;
1652 j3=((-1.0)*(IKacos(gconst18)));
1653 CheckValue<IkReal> x124=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
1654 if(!x124.valid){
1655 continue;
1656 }
1657 if((x124.value) < -0.00001)
1658 continue;
1659 IkReal gconst18=((-1.0)*(IKsqrt(x124.value)));
1660 j5eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
1661 if( IKabs(j5eval[0]) < 0.0000010000000000 )
1662 {
1663 {
1664 IkReal j5array[1], cj5array[1], sj5array[1];
1665 bool j5valid[1]={false};
1666 _nj5 = 1;
1667 if((((1.0)+(((-1.0)*(gconst18*gconst18))))) < -0.00001)
1668 continue;
1669 CheckValue<IkReal> x125=IKPowWithIntegerCheck(gconst18,-1);
1670 if(!x125.valid){
1671 continue;
1672 }
1673 if( IKabs((((gconst18*new_r10))+((new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18)))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r11*(x125.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((gconst18*new_r10))+((new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18))))))))))+IKsqr((new_r11*(x125.value)))-1) <= IKFAST_SINCOS_THRESH )
1674  continue;
1675 j5array[0]=IKatan2((((gconst18*new_r10))+((new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst18*gconst18))))))))), (new_r11*(x125.value)));
1676 sj5array[0]=IKsin(j5array[0]);
1677 cj5array[0]=IKcos(j5array[0]);
1678 if( j5array[0] > IKPI )
1679 {
1680  j5array[0]-=IK2PI;
1681 }
1682 else if( j5array[0] < -IKPI )
1683 { j5array[0]+=IK2PI;
1684 }
1685 j5valid[0] = true;
1686 for(int ij5 = 0; ij5 < 1; ++ij5)
1687 {
1688 if( !j5valid[ij5] )
1689 {
1690  continue;
1691 }
1692 _ij5[0] = ij5; _ij5[1] = -1;
1693 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1694 {
1695 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1696 {
1697  j5valid[iij5]=false; _ij5[1] = iij5; break;
1698 }
1699 }
1700 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1701 {
1702 IkReal evalcond[8];
1703 IkReal x126=IKcos(j5);
1704 IkReal x127=IKsin(j5);
1705 IkReal x128=((1.0)*gconst18);
1706 if((((1.0)+(((-1.0)*gconst18*x128)))) < -0.00001)
1707 continue;
1708 IkReal x129=IKsqrt(((1.0)+(((-1.0)*gconst18*x128))));
1709 IkReal x130=((1.0)*x129);
1710 evalcond[0]=x126;
1711 evalcond[1]=((-1.0)*x127);
1712 evalcond[2]=((((-1.0)*x126*x128))+new_r11);
1713 evalcond[3]=(new_r10+(((-1.0)*x127*x128)));
1714 evalcond[4]=((((-1.0)*x126*x130))+new_r01);
1715 evalcond[5]=(new_r00+(((-1.0)*x127*x130)));
1716 evalcond[6]=((((-1.0)*new_r10*x128))+(((-1.0)*new_r00*x130))+x127);
1717 evalcond[7]=((((-1.0)*new_r01*x130))+x126+(((-1.0)*new_r11*x128)));
1718 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
1719 {
1720 continue;
1721 }
1722 }
1723 
1724 {
1725 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1726 vinfos[0].jointtype = 1;
1727 vinfos[0].foffset = j0;
1728 vinfos[0].indices[0] = _ij0[0];
1729 vinfos[0].indices[1] = _ij0[1];
1730 vinfos[0].maxsolutions = _nj0;
1731 vinfos[1].jointtype = 1;
1732 vinfos[1].foffset = j1;
1733 vinfos[1].indices[0] = _ij1[0];
1734 vinfos[1].indices[1] = _ij1[1];
1735 vinfos[1].maxsolutions = _nj1;
1736 vinfos[2].jointtype = 1;
1737 vinfos[2].foffset = j2;
1738 vinfos[2].indices[0] = _ij2[0];
1739 vinfos[2].indices[1] = _ij2[1];
1740 vinfos[2].maxsolutions = _nj2;
1741 vinfos[3].jointtype = 1;
1742 vinfos[3].foffset = j3;
1743 vinfos[3].indices[0] = _ij3[0];
1744 vinfos[3].indices[1] = _ij3[1];
1745 vinfos[3].maxsolutions = _nj3;
1746 vinfos[4].jointtype = 1;
1747 vinfos[4].foffset = j4;
1748 vinfos[4].indices[0] = _ij4[0];
1749 vinfos[4].indices[1] = _ij4[1];
1750 vinfos[4].maxsolutions = _nj4;
1751 vinfos[5].jointtype = 1;
1752 vinfos[5].foffset = j5;
1753 vinfos[5].indices[0] = _ij5[0];
1754 vinfos[5].indices[1] = _ij5[1];
1755 vinfos[5].maxsolutions = _nj5;
1756 std::vector<int> vfree(0);
1757 solutions.AddSolution(vinfos,vfree);
1758 }
1759 }
1760 }
1761 
1762 } else
1763 {
1764 {
1765 IkReal j5array[1], cj5array[1], sj5array[1];
1766 bool j5valid[1]={false};
1767 _nj5 = 1;
1769 if(!x131.valid){
1770 continue;
1771 }
1772 CheckValue<IkReal> x132 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
1773 if(!x132.valid){
1774 continue;
1775 }
1776 j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x131.value)))+(x132.value));
1777 sj5array[0]=IKsin(j5array[0]);
1778 cj5array[0]=IKcos(j5array[0]);
1779 if( j5array[0] > IKPI )
1780 {
1781  j5array[0]-=IK2PI;
1782 }
1783 else if( j5array[0] < -IKPI )
1784 { j5array[0]+=IK2PI;
1785 }
1786 j5valid[0] = true;
1787 for(int ij5 = 0; ij5 < 1; ++ij5)
1788 {
1789 if( !j5valid[ij5] )
1790 {
1791  continue;
1792 }
1793 _ij5[0] = ij5; _ij5[1] = -1;
1794 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1795 {
1796 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1797 {
1798  j5valid[iij5]=false; _ij5[1] = iij5; break;
1799 }
1800 }
1801 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1802 {
1803 IkReal evalcond[8];
1804 IkReal x133=IKcos(j5);
1805 IkReal x134=IKsin(j5);
1806 IkReal x135=((1.0)*gconst18);
1807 if((((1.0)+(((-1.0)*gconst18*x135)))) < -0.00001)
1808 continue;
1809 IkReal x136=IKsqrt(((1.0)+(((-1.0)*gconst18*x135))));
1810 IkReal x137=((1.0)*x136);
1811 evalcond[0]=x133;
1812 evalcond[1]=((-1.0)*x134);
1813 evalcond[2]=((((-1.0)*x133*x135))+new_r11);
1814 evalcond[3]=((((-1.0)*x134*x135))+new_r10);
1815 evalcond[4]=((((-1.0)*x133*x137))+new_r01);
1816 evalcond[5]=((((-1.0)*x134*x137))+new_r00);
1817 evalcond[6]=((((-1.0)*new_r10*x135))+(((-1.0)*new_r00*x137))+x134);
1818 evalcond[7]=((((-1.0)*new_r11*x135))+(((-1.0)*new_r01*x137))+x133);
1819 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
1820 {
1821 continue;
1822 }
1823 }
1824 
1825 {
1826 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1827 vinfos[0].jointtype = 1;
1828 vinfos[0].foffset = j0;
1829 vinfos[0].indices[0] = _ij0[0];
1830 vinfos[0].indices[1] = _ij0[1];
1831 vinfos[0].maxsolutions = _nj0;
1832 vinfos[1].jointtype = 1;
1833 vinfos[1].foffset = j1;
1834 vinfos[1].indices[0] = _ij1[0];
1835 vinfos[1].indices[1] = _ij1[1];
1836 vinfos[1].maxsolutions = _nj1;
1837 vinfos[2].jointtype = 1;
1838 vinfos[2].foffset = j2;
1839 vinfos[2].indices[0] = _ij2[0];
1840 vinfos[2].indices[1] = _ij2[1];
1841 vinfos[2].maxsolutions = _nj2;
1842 vinfos[3].jointtype = 1;
1843 vinfos[3].foffset = j3;
1844 vinfos[3].indices[0] = _ij3[0];
1845 vinfos[3].indices[1] = _ij3[1];
1846 vinfos[3].maxsolutions = _nj3;
1847 vinfos[4].jointtype = 1;
1848 vinfos[4].foffset = j4;
1849 vinfos[4].indices[0] = _ij4[0];
1850 vinfos[4].indices[1] = _ij4[1];
1851 vinfos[4].maxsolutions = _nj4;
1852 vinfos[5].jointtype = 1;
1853 vinfos[5].foffset = j5;
1854 vinfos[5].indices[0] = _ij5[0];
1855 vinfos[5].indices[1] = _ij5[1];
1856 vinfos[5].maxsolutions = _nj5;
1857 std::vector<int> vfree(0);
1858 solutions.AddSolution(vinfos,vfree);
1859 }
1860 }
1861 }
1862 
1863 }
1864 
1865 }
1866 
1867 }
1868 } while(0);
1869 if( bgotonextstatement )
1870 {
1871 bool bgotonextstatement = true;
1872 do
1873 {
1874 CheckValue<IkReal> x138=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
1875 if(!x138.valid){
1876 continue;
1877 }
1878 if((x138.value) < -0.00001)
1879 continue;
1880 IkReal gconst19=IKsqrt(x138.value);
1881 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst19)))))), 6.28318530717959)));
1882 if( IKabs(evalcond[0]) < 0.0000050000000000 )
1883 {
1884 bgotonextstatement=false;
1885 {
1886 IkReal j5eval[1];
1887 new_r21=0;
1888 new_r20=0;
1889 new_r02=0;
1890 new_r12=0;
1891 if((((1.0)+(((-1.0)*(gconst19*gconst19))))) < -0.00001)
1892 continue;
1893 sj3=IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19)))));
1894 cj3=gconst19;
1895 if( (gconst19) < -1-IKFAST_SINCOS_THRESH || (gconst19) > 1+IKFAST_SINCOS_THRESH )
1896  continue;
1897 j3=IKacos(gconst19);
1898 CheckValue<IkReal> x139=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
1899 if(!x139.valid){
1900 continue;
1901 }
1902 if((x139.value) < -0.00001)
1903 continue;
1904 IkReal gconst19=IKsqrt(x139.value);
1905 j5eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
1906 if( IKabs(j5eval[0]) < 0.0000010000000000 )
1907 {
1908 {
1909 IkReal j5array[1], cj5array[1], sj5array[1];
1910 bool j5valid[1]={false};
1911 _nj5 = 1;
1912 if((((1.0)+(((-1.0)*(gconst19*gconst19))))) < -0.00001)
1913 continue;
1914 CheckValue<IkReal> x140=IKPowWithIntegerCheck(gconst19,-1);
1915 if(!x140.valid){
1916 continue;
1917 }
1918 if( IKabs((((gconst19*new_r10))+(((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19)))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r11*(x140.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((gconst19*new_r10))+(((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19))))))))))+IKsqr((new_r11*(x140.value)))-1) <= IKFAST_SINCOS_THRESH )
1919  continue;
1920 j5array[0]=IKatan2((((gconst19*new_r10))+(((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19))))))))), (new_r11*(x140.value)));
1921 sj5array[0]=IKsin(j5array[0]);
1922 cj5array[0]=IKcos(j5array[0]);
1923 if( j5array[0] > IKPI )
1924 {
1925  j5array[0]-=IK2PI;
1926 }
1927 else if( j5array[0] < -IKPI )
1928 { j5array[0]+=IK2PI;
1929 }
1930 j5valid[0] = true;
1931 for(int ij5 = 0; ij5 < 1; ++ij5)
1932 {
1933 if( !j5valid[ij5] )
1934 {
1935  continue;
1936 }
1937 _ij5[0] = ij5; _ij5[1] = -1;
1938 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1939 {
1940 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1941 {
1942  j5valid[iij5]=false; _ij5[1] = iij5; break;
1943 }
1944 }
1945 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1946 {
1947 IkReal evalcond[8];
1948 IkReal x141=IKcos(j5);
1949 IkReal x142=IKsin(j5);
1950 IkReal x143=((1.0)*gconst19);
1951 if((((1.0)+(((-1.0)*gconst19*x143)))) < -0.00001)
1952 continue;
1953 IkReal x144=IKsqrt(((1.0)+(((-1.0)*gconst19*x143))));
1954 evalcond[0]=x141;
1955 evalcond[1]=((-1.0)*x142);
1956 evalcond[2]=((((-1.0)*x141*x143))+new_r11);
1957 evalcond[3]=((((-1.0)*x142*x143))+new_r10);
1958 evalcond[4]=(((x141*x144))+new_r01);
1959 evalcond[5]=(((x142*x144))+new_r00);
1960 evalcond[6]=(((new_r00*x144))+x142+(((-1.0)*new_r10*x143)));
1961 evalcond[7]=(((new_r01*x144))+(((-1.0)*new_r11*x143))+x141);
1962 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
1963 {
1964 continue;
1965 }
1966 }
1967 
1968 {
1969 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1970 vinfos[0].jointtype = 1;
1971 vinfos[0].foffset = j0;
1972 vinfos[0].indices[0] = _ij0[0];
1973 vinfos[0].indices[1] = _ij0[1];
1974 vinfos[0].maxsolutions = _nj0;
1975 vinfos[1].jointtype = 1;
1976 vinfos[1].foffset = j1;
1977 vinfos[1].indices[0] = _ij1[0];
1978 vinfos[1].indices[1] = _ij1[1];
1979 vinfos[1].maxsolutions = _nj1;
1980 vinfos[2].jointtype = 1;
1981 vinfos[2].foffset = j2;
1982 vinfos[2].indices[0] = _ij2[0];
1983 vinfos[2].indices[1] = _ij2[1];
1984 vinfos[2].maxsolutions = _nj2;
1985 vinfos[3].jointtype = 1;
1986 vinfos[3].foffset = j3;
1987 vinfos[3].indices[0] = _ij3[0];
1988 vinfos[3].indices[1] = _ij3[1];
1989 vinfos[3].maxsolutions = _nj3;
1990 vinfos[4].jointtype = 1;
1991 vinfos[4].foffset = j4;
1992 vinfos[4].indices[0] = _ij4[0];
1993 vinfos[4].indices[1] = _ij4[1];
1994 vinfos[4].maxsolutions = _nj4;
1995 vinfos[5].jointtype = 1;
1996 vinfos[5].foffset = j5;
1997 vinfos[5].indices[0] = _ij5[0];
1998 vinfos[5].indices[1] = _ij5[1];
1999 vinfos[5].maxsolutions = _nj5;
2000 std::vector<int> vfree(0);
2001 solutions.AddSolution(vinfos,vfree);
2002 }
2003 }
2004 }
2005 
2006 } else
2007 {
2008 {
2009 IkReal j5array[1], cj5array[1], sj5array[1];
2010 bool j5valid[1]={false};
2011 _nj5 = 1;
2013 if(!x145.valid){
2014 continue;
2015 }
2016 CheckValue<IkReal> x146 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
2017 if(!x146.valid){
2018 continue;
2019 }
2020 j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x145.value)))+(x146.value));
2021 sj5array[0]=IKsin(j5array[0]);
2022 cj5array[0]=IKcos(j5array[0]);
2023 if( j5array[0] > IKPI )
2024 {
2025  j5array[0]-=IK2PI;
2026 }
2027 else if( j5array[0] < -IKPI )
2028 { j5array[0]+=IK2PI;
2029 }
2030 j5valid[0] = true;
2031 for(int ij5 = 0; ij5 < 1; ++ij5)
2032 {
2033 if( !j5valid[ij5] )
2034 {
2035  continue;
2036 }
2037 _ij5[0] = ij5; _ij5[1] = -1;
2038 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2039 {
2040 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2041 {
2042  j5valid[iij5]=false; _ij5[1] = iij5; break;
2043 }
2044 }
2045 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2046 {
2047 IkReal evalcond[8];
2048 IkReal x147=IKcos(j5);
2049 IkReal x148=IKsin(j5);
2050 IkReal x149=((1.0)*gconst19);
2051 if((((1.0)+(((-1.0)*gconst19*x149)))) < -0.00001)
2052 continue;
2053 IkReal x150=IKsqrt(((1.0)+(((-1.0)*gconst19*x149))));
2054 evalcond[0]=x147;
2055 evalcond[1]=((-1.0)*x148);
2056 evalcond[2]=((((-1.0)*x147*x149))+new_r11);
2057 evalcond[3]=((((-1.0)*x148*x149))+new_r10);
2058 evalcond[4]=(((x147*x150))+new_r01);
2059 evalcond[5]=(((x148*x150))+new_r00);
2060 evalcond[6]=(((new_r00*x150))+x148+(((-1.0)*new_r10*x149)));
2061 evalcond[7]=(((new_r01*x150))+(((-1.0)*new_r11*x149))+x147);
2062 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
2063 {
2064 continue;
2065 }
2066 }
2067 
2068 {
2069 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2070 vinfos[0].jointtype = 1;
2071 vinfos[0].foffset = j0;
2072 vinfos[0].indices[0] = _ij0[0];
2073 vinfos[0].indices[1] = _ij0[1];
2074 vinfos[0].maxsolutions = _nj0;
2075 vinfos[1].jointtype = 1;
2076 vinfos[1].foffset = j1;
2077 vinfos[1].indices[0] = _ij1[0];
2078 vinfos[1].indices[1] = _ij1[1];
2079 vinfos[1].maxsolutions = _nj1;
2080 vinfos[2].jointtype = 1;
2081 vinfos[2].foffset = j2;
2082 vinfos[2].indices[0] = _ij2[0];
2083 vinfos[2].indices[1] = _ij2[1];
2084 vinfos[2].maxsolutions = _nj2;
2085 vinfos[3].jointtype = 1;
2086 vinfos[3].foffset = j3;
2087 vinfos[3].indices[0] = _ij3[0];
2088 vinfos[3].indices[1] = _ij3[1];
2089 vinfos[3].maxsolutions = _nj3;
2090 vinfos[4].jointtype = 1;
2091 vinfos[4].foffset = j4;
2092 vinfos[4].indices[0] = _ij4[0];
2093 vinfos[4].indices[1] = _ij4[1];
2094 vinfos[4].maxsolutions = _nj4;
2095 vinfos[5].jointtype = 1;
2096 vinfos[5].foffset = j5;
2097 vinfos[5].indices[0] = _ij5[0];
2098 vinfos[5].indices[1] = _ij5[1];
2099 vinfos[5].maxsolutions = _nj5;
2100 std::vector<int> vfree(0);
2101 solutions.AddSolution(vinfos,vfree);
2102 }
2103 }
2104 }
2105 
2106 }
2107 
2108 }
2109 
2110 }
2111 } while(0);
2112 if( bgotonextstatement )
2113 {
2114 bool bgotonextstatement = true;
2115 do
2116 {
2117 CheckValue<IkReal> x151=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
2118 if(!x151.valid){
2119 continue;
2120 }
2121 if((x151.value) < -0.00001)
2122 continue;
2123 IkReal gconst19=IKsqrt(x151.value);
2124 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst19)))))), 6.28318530717959)));
2125 if( IKabs(evalcond[0]) < 0.0000050000000000 )
2126 {
2127 bgotonextstatement=false;
2128 {
2129 IkReal j5eval[1];
2130 new_r21=0;
2131 new_r20=0;
2132 new_r02=0;
2133 new_r12=0;
2134 if((((1.0)+(((-1.0)*(gconst19*gconst19))))) < -0.00001)
2135 continue;
2136 sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19)))))));
2137 cj3=gconst19;
2138 if( (gconst19) < -1-IKFAST_SINCOS_THRESH || (gconst19) > 1+IKFAST_SINCOS_THRESH )
2139  continue;
2140 j3=((-1.0)*(IKacos(gconst19)));
2141 CheckValue<IkReal> x152=IKPowWithIntegerCheck(((1.0)+(((-1.0)*(new_r22*new_r22)))),-1);
2142 if(!x152.valid){
2143 continue;
2144 }
2145 if((x152.value) < -0.00001)
2146 continue;
2147 IkReal gconst19=IKsqrt(x152.value);
2148 j5eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
2149 if( IKabs(j5eval[0]) < 0.0000010000000000 )
2150 {
2151 {
2152 IkReal j5array[1], cj5array[1], sj5array[1];
2153 bool j5valid[1]={false};
2154 _nj5 = 1;
2155 if((((1.0)+(((-1.0)*(gconst19*gconst19))))) < -0.00001)
2156 continue;
2157 CheckValue<IkReal> x153=IKPowWithIntegerCheck(gconst19,-1);
2158 if(!x153.valid){
2159 continue;
2160 }
2161 if( IKabs((((new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19))))))))+((gconst19*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r11*(x153.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19))))))))+((gconst19*new_r10))))+IKsqr((new_r11*(x153.value)))-1) <= IKFAST_SINCOS_THRESH )
2162  continue;
2163 j5array[0]=IKatan2((((new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst19*gconst19))))))))+((gconst19*new_r10))), (new_r11*(x153.value)));
2164 sj5array[0]=IKsin(j5array[0]);
2165 cj5array[0]=IKcos(j5array[0]);
2166 if( j5array[0] > IKPI )
2167 {
2168  j5array[0]-=IK2PI;
2169 }
2170 else if( j5array[0] < -IKPI )
2171 { j5array[0]+=IK2PI;
2172 }
2173 j5valid[0] = true;
2174 for(int ij5 = 0; ij5 < 1; ++ij5)
2175 {
2176 if( !j5valid[ij5] )
2177 {
2178  continue;
2179 }
2180 _ij5[0] = ij5; _ij5[1] = -1;
2181 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2182 {
2183 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2184 {
2185  j5valid[iij5]=false; _ij5[1] = iij5; break;
2186 }
2187 }
2188 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2189 {
2190 IkReal evalcond[8];
2191 IkReal x154=IKcos(j5);
2192 IkReal x155=IKsin(j5);
2193 IkReal x156=((1.0)*gconst19);
2194 if((((1.0)+(((-1.0)*gconst19*x156)))) < -0.00001)
2195 continue;
2196 IkReal x157=IKsqrt(((1.0)+(((-1.0)*gconst19*x156))));
2197 IkReal x158=((1.0)*x157);
2198 evalcond[0]=x154;
2199 evalcond[1]=((-1.0)*x155);
2200 evalcond[2]=((((-1.0)*x154*x156))+new_r11);
2201 evalcond[3]=((((-1.0)*x155*x156))+new_r10);
2202 evalcond[4]=((((-1.0)*x154*x158))+new_r01);
2203 evalcond[5]=((((-1.0)*x155*x158))+new_r00);
2204 evalcond[6]=(x155+(((-1.0)*new_r10*x156))+(((-1.0)*new_r00*x158)));
2205 evalcond[7]=(x154+(((-1.0)*new_r11*x156))+(((-1.0)*new_r01*x158)));
2206 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
2207 {
2208 continue;
2209 }
2210 }
2211 
2212 {
2213 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2214 vinfos[0].jointtype = 1;
2215 vinfos[0].foffset = j0;
2216 vinfos[0].indices[0] = _ij0[0];
2217 vinfos[0].indices[1] = _ij0[1];
2218 vinfos[0].maxsolutions = _nj0;
2219 vinfos[1].jointtype = 1;
2220 vinfos[1].foffset = j1;
2221 vinfos[1].indices[0] = _ij1[0];
2222 vinfos[1].indices[1] = _ij1[1];
2223 vinfos[1].maxsolutions = _nj1;
2224 vinfos[2].jointtype = 1;
2225 vinfos[2].foffset = j2;
2226 vinfos[2].indices[0] = _ij2[0];
2227 vinfos[2].indices[1] = _ij2[1];
2228 vinfos[2].maxsolutions = _nj2;
2229 vinfos[3].jointtype = 1;
2230 vinfos[3].foffset = j3;
2231 vinfos[3].indices[0] = _ij3[0];
2232 vinfos[3].indices[1] = _ij3[1];
2233 vinfos[3].maxsolutions = _nj3;
2234 vinfos[4].jointtype = 1;
2235 vinfos[4].foffset = j4;
2236 vinfos[4].indices[0] = _ij4[0];
2237 vinfos[4].indices[1] = _ij4[1];
2238 vinfos[4].maxsolutions = _nj4;
2239 vinfos[5].jointtype = 1;
2240 vinfos[5].foffset = j5;
2241 vinfos[5].indices[0] = _ij5[0];
2242 vinfos[5].indices[1] = _ij5[1];
2243 vinfos[5].maxsolutions = _nj5;
2244 std::vector<int> vfree(0);
2245 solutions.AddSolution(vinfos,vfree);
2246 }
2247 }
2248 }
2249 
2250 } else
2251 {
2252 {
2253 IkReal j5array[1], cj5array[1], sj5array[1];
2254 bool j5valid[1]={false};
2255 _nj5 = 1;
2257 if(!x159.valid){
2258 continue;
2259 }
2260 CheckValue<IkReal> x160 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
2261 if(!x160.valid){
2262 continue;
2263 }
2264 j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x159.value)))+(x160.value));
2265 sj5array[0]=IKsin(j5array[0]);
2266 cj5array[0]=IKcos(j5array[0]);
2267 if( j5array[0] > IKPI )
2268 {
2269  j5array[0]-=IK2PI;
2270 }
2271 else if( j5array[0] < -IKPI )
2272 { j5array[0]+=IK2PI;
2273 }
2274 j5valid[0] = true;
2275 for(int ij5 = 0; ij5 < 1; ++ij5)
2276 {
2277 if( !j5valid[ij5] )
2278 {
2279  continue;
2280 }
2281 _ij5[0] = ij5; _ij5[1] = -1;
2282 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2283 {
2284 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2285 {
2286  j5valid[iij5]=false; _ij5[1] = iij5; break;
2287 }
2288 }
2289 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2290 {
2291 IkReal evalcond[8];
2292 IkReal x161=IKcos(j5);
2293 IkReal x162=IKsin(j5);
2294 IkReal x163=((1.0)*gconst19);
2295 if((((1.0)+(((-1.0)*gconst19*x163)))) < -0.00001)
2296 continue;
2297 IkReal x164=IKsqrt(((1.0)+(((-1.0)*gconst19*x163))));
2298 IkReal x165=((1.0)*x164);
2299 evalcond[0]=x161;
2300 evalcond[1]=((-1.0)*x162);
2301 evalcond[2]=((((-1.0)*x161*x163))+new_r11);
2302 evalcond[3]=((((-1.0)*x162*x163))+new_r10);
2303 evalcond[4]=((((-1.0)*x161*x165))+new_r01);
2304 evalcond[5]=((((-1.0)*x162*x165))+new_r00);
2305 evalcond[6]=((((-1.0)*new_r00*x165))+(((-1.0)*new_r10*x163))+x162);
2306 evalcond[7]=((((-1.0)*new_r11*x163))+x161+(((-1.0)*new_r01*x165)));
2307 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
2308 {
2309 continue;
2310 }
2311 }
2312 
2313 {
2314 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2315 vinfos[0].jointtype = 1;
2316 vinfos[0].foffset = j0;
2317 vinfos[0].indices[0] = _ij0[0];
2318 vinfos[0].indices[1] = _ij0[1];
2319 vinfos[0].maxsolutions = _nj0;
2320 vinfos[1].jointtype = 1;
2321 vinfos[1].foffset = j1;
2322 vinfos[1].indices[0] = _ij1[0];
2323 vinfos[1].indices[1] = _ij1[1];
2324 vinfos[1].maxsolutions = _nj1;
2325 vinfos[2].jointtype = 1;
2326 vinfos[2].foffset = j2;
2327 vinfos[2].indices[0] = _ij2[0];
2328 vinfos[2].indices[1] = _ij2[1];
2329 vinfos[2].maxsolutions = _nj2;
2330 vinfos[3].jointtype = 1;
2331 vinfos[3].foffset = j3;
2332 vinfos[3].indices[0] = _ij3[0];
2333 vinfos[3].indices[1] = _ij3[1];
2334 vinfos[3].maxsolutions = _nj3;
2335 vinfos[4].jointtype = 1;
2336 vinfos[4].foffset = j4;
2337 vinfos[4].indices[0] = _ij4[0];
2338 vinfos[4].indices[1] = _ij4[1];
2339 vinfos[4].maxsolutions = _nj4;
2340 vinfos[5].jointtype = 1;
2341 vinfos[5].foffset = j5;
2342 vinfos[5].indices[0] = _ij5[0];
2343 vinfos[5].indices[1] = _ij5[1];
2344 vinfos[5].maxsolutions = _nj5;
2345 std::vector<int> vfree(0);
2346 solutions.AddSolution(vinfos,vfree);
2347 }
2348 }
2349 }
2350 
2351 }
2352 
2353 }
2354 
2355 }
2356 } while(0);
2357 if( bgotonextstatement )
2358 {
2359 bool bgotonextstatement = true;
2360 do
2361 {
2362 if( 1 )
2363 {
2364 bgotonextstatement=false;
2365 continue; // branch miss [j5]
2366 
2367 }
2368 } while(0);
2369 if( bgotonextstatement )
2370 {
2371 }
2372 }
2373 }
2374 }
2375 }
2376 }
2377 }
2378 }
2379 
2380 } else
2381 {
2382 {
2383 IkReal j5array[1], cj5array[1], sj5array[1];
2384 bool j5valid[1]={false};
2385 _nj5 = 1;
2386 IkReal x166=(new_r00*sj3);
2388 if(!x167.valid){
2389 continue;
2390 }
2391 if( IKabs(((((-1.0)*x166))+((cj3*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x167.value)*((((cj3*new_r22*x166))+(((-1.0)*new_r01))+(((-1.0)*new_r10*new_r22*(cj3*cj3))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x166))+((cj3*new_r10))))+IKsqr(((x167.value)*((((cj3*new_r22*x166))+(((-1.0)*new_r01))+(((-1.0)*new_r10*new_r22*(cj3*cj3)))))))-1) <= IKFAST_SINCOS_THRESH )
2392  continue;
2393 j5array[0]=IKatan2(((((-1.0)*x166))+((cj3*new_r10))), ((x167.value)*((((cj3*new_r22*x166))+(((-1.0)*new_r01))+(((-1.0)*new_r10*new_r22*(cj3*cj3)))))));
2394 sj5array[0]=IKsin(j5array[0]);
2395 cj5array[0]=IKcos(j5array[0]);
2396 if( j5array[0] > IKPI )
2397 {
2398  j5array[0]-=IK2PI;
2399 }
2400 else if( j5array[0] < -IKPI )
2401 { j5array[0]+=IK2PI;
2402 }
2403 j5valid[0] = true;
2404 for(int ij5 = 0; ij5 < 1; ++ij5)
2405 {
2406 if( !j5valid[ij5] )
2407 {
2408  continue;
2409 }
2410 _ij5[0] = ij5; _ij5[1] = -1;
2411 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2412 {
2413 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2414 {
2415  j5valid[iij5]=false; _ij5[1] = iij5; break;
2416 }
2417 }
2418 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2419 {
2420 IkReal evalcond[10];
2421 IkReal x168=IKsin(j5);
2422 IkReal x169=IKcos(j5);
2423 IkReal x170=((1.0)*new_r11);
2424 IkReal x171=(new_r22*sj3);
2425 IkReal x172=((1.0)*new_r10);
2426 IkReal x173=((1.0)*cj3*new_r22);
2427 IkReal x174=(sj3*x168);
2428 IkReal x175=(new_r22*x168);
2429 IkReal x176=((1.0)*x169);
2430 IkReal x177=((1.0)*x168);
2431 evalcond[0]=(((new_r00*sj3))+x168+(((-1.0)*cj3*x172)));
2432 evalcond[1]=(((new_r01*sj3))+x169+(((-1.0)*cj3*x170)));
2433 evalcond[2]=(((new_r11*sj3))+x175+((cj3*new_r01)));
2434 evalcond[3]=(((sj3*x169))+((cj3*x175))+new_r01);
2435 evalcond[4]=(((new_r10*sj3))+(((-1.0)*new_r22*x176))+((cj3*new_r00)));
2436 evalcond[5]=(x174+new_r00+(((-1.0)*x169*x173)));
2437 evalcond[6]=(((x168*x171))+(((-1.0)*cj3*x176))+new_r11);
2438 evalcond[7]=(x169+(((-1.0)*x171*x172))+(((-1.0)*new_r00*x173)));
2439 evalcond[8]=((((-1.0)*cj3*x177))+(((-1.0)*x171*x176))+new_r10);
2440 evalcond[9]=((((-1.0)*x177))+(((-1.0)*x170*x171))+(((-1.0)*new_r01*x173)));
2441 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
2442 {
2443 continue;
2444 }
2445 }
2446 
2447 {
2448 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2449 vinfos[0].jointtype = 1;
2450 vinfos[0].foffset = j0;
2451 vinfos[0].indices[0] = _ij0[0];
2452 vinfos[0].indices[1] = _ij0[1];
2453 vinfos[0].maxsolutions = _nj0;
2454 vinfos[1].jointtype = 1;
2455 vinfos[1].foffset = j1;
2456 vinfos[1].indices[0] = _ij1[0];
2457 vinfos[1].indices[1] = _ij1[1];
2458 vinfos[1].maxsolutions = _nj1;
2459 vinfos[2].jointtype = 1;
2460 vinfos[2].foffset = j2;
2461 vinfos[2].indices[0] = _ij2[0];
2462 vinfos[2].indices[1] = _ij2[1];
2463 vinfos[2].maxsolutions = _nj2;
2464 vinfos[3].jointtype = 1;
2465 vinfos[3].foffset = j3;
2466 vinfos[3].indices[0] = _ij3[0];
2467 vinfos[3].indices[1] = _ij3[1];
2468 vinfos[3].maxsolutions = _nj3;
2469 vinfos[4].jointtype = 1;
2470 vinfos[4].foffset = j4;
2471 vinfos[4].indices[0] = _ij4[0];
2472 vinfos[4].indices[1] = _ij4[1];
2473 vinfos[4].maxsolutions = _nj4;
2474 vinfos[5].jointtype = 1;
2475 vinfos[5].foffset = j5;
2476 vinfos[5].indices[0] = _ij5[0];
2477 vinfos[5].indices[1] = _ij5[1];
2478 vinfos[5].maxsolutions = _nj5;
2479 std::vector<int> vfree(0);
2480 solutions.AddSolution(vinfos,vfree);
2481 }
2482 }
2483 }
2484 
2485 }
2486 
2487 }
2488 
2489 } else
2490 {
2491 {
2492 IkReal j5array[1], cj5array[1], sj5array[1];
2493 bool j5valid[1]={false};
2494 _nj5 = 1;
2495 IkReal x178=((1.0)*new_r01);
2496 CheckValue<IkReal> x179=IKPowWithIntegerCheck(new_r22,-1);
2497 if(!x179.valid){
2498 continue;
2499 }
2500 if( IKabs(((x179.value)*(((((-1.0)*cj3*x178))+(((-1.0)*new_r11*sj3)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj3*new_r11))+(((-1.0)*sj3*x178)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x179.value)*(((((-1.0)*cj3*x178))+(((-1.0)*new_r11*sj3))))))+IKsqr((((cj3*new_r11))+(((-1.0)*sj3*x178))))-1) <= IKFAST_SINCOS_THRESH )
2501  continue;
2502 j5array[0]=IKatan2(((x179.value)*(((((-1.0)*cj3*x178))+(((-1.0)*new_r11*sj3))))), (((cj3*new_r11))+(((-1.0)*sj3*x178))));
2503 sj5array[0]=IKsin(j5array[0]);
2504 cj5array[0]=IKcos(j5array[0]);
2505 if( j5array[0] > IKPI )
2506 {
2507  j5array[0]-=IK2PI;
2508 }
2509 else if( j5array[0] < -IKPI )
2510 { j5array[0]+=IK2PI;
2511 }
2512 j5valid[0] = true;
2513 for(int ij5 = 0; ij5 < 1; ++ij5)
2514 {
2515 if( !j5valid[ij5] )
2516 {
2517  continue;
2518 }
2519 _ij5[0] = ij5; _ij5[1] = -1;
2520 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2521 {
2522 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2523 {
2524  j5valid[iij5]=false; _ij5[1] = iij5; break;
2525 }
2526 }
2527 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2528 {
2529 IkReal evalcond[10];
2530 IkReal x180=IKsin(j5);
2531 IkReal x181=IKcos(j5);
2532 IkReal x182=((1.0)*new_r11);
2533 IkReal x183=(new_r22*sj3);
2534 IkReal x184=((1.0)*new_r10);
2535 IkReal x185=((1.0)*cj3*new_r22);
2536 IkReal x186=(sj3*x180);
2537 IkReal x187=(new_r22*x180);
2538 IkReal x188=((1.0)*x181);
2539 IkReal x189=((1.0)*x180);
2540 evalcond[0]=(((new_r00*sj3))+x180+(((-1.0)*cj3*x184)));
2541 evalcond[1]=(((new_r01*sj3))+x181+(((-1.0)*cj3*x182)));
2542 evalcond[2]=(((new_r11*sj3))+x187+((cj3*new_r01)));
2543 evalcond[3]=(((sj3*x181))+((cj3*x187))+new_r01);
2544 evalcond[4]=(((new_r10*sj3))+(((-1.0)*new_r22*x188))+((cj3*new_r00)));
2545 evalcond[5]=(x186+new_r00+(((-1.0)*x181*x185)));
2546 evalcond[6]=(((x180*x183))+new_r11+(((-1.0)*cj3*x188)));
2547 evalcond[7]=(x181+(((-1.0)*new_r00*x185))+(((-1.0)*x183*x184)));
2548 evalcond[8]=(new_r10+(((-1.0)*x183*x188))+(((-1.0)*cj3*x189)));
2549 evalcond[9]=((((-1.0)*x189))+(((-1.0)*new_r01*x185))+(((-1.0)*x182*x183)));
2550 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
2551 {
2552 continue;
2553 }
2554 }
2555 
2556 {
2557 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2558 vinfos[0].jointtype = 1;
2559 vinfos[0].foffset = j0;
2560 vinfos[0].indices[0] = _ij0[0];
2561 vinfos[0].indices[1] = _ij0[1];
2562 vinfos[0].maxsolutions = _nj0;
2563 vinfos[1].jointtype = 1;
2564 vinfos[1].foffset = j1;
2565 vinfos[1].indices[0] = _ij1[0];
2566 vinfos[1].indices[1] = _ij1[1];
2567 vinfos[1].maxsolutions = _nj1;
2568 vinfos[2].jointtype = 1;
2569 vinfos[2].foffset = j2;
2570 vinfos[2].indices[0] = _ij2[0];
2571 vinfos[2].indices[1] = _ij2[1];
2572 vinfos[2].maxsolutions = _nj2;
2573 vinfos[3].jointtype = 1;
2574 vinfos[3].foffset = j3;
2575 vinfos[3].indices[0] = _ij3[0];
2576 vinfos[3].indices[1] = _ij3[1];
2577 vinfos[3].maxsolutions = _nj3;
2578 vinfos[4].jointtype = 1;
2579 vinfos[4].foffset = j4;
2580 vinfos[4].indices[0] = _ij4[0];
2581 vinfos[4].indices[1] = _ij4[1];
2582 vinfos[4].maxsolutions = _nj4;
2583 vinfos[5].jointtype = 1;
2584 vinfos[5].foffset = j5;
2585 vinfos[5].indices[0] = _ij5[0];
2586 vinfos[5].indices[1] = _ij5[1];
2587 vinfos[5].maxsolutions = _nj5;
2588 std::vector<int> vfree(0);
2589 solutions.AddSolution(vinfos,vfree);
2590 }
2591 }
2592 }
2593 
2594 }
2595 
2596 }
2597 
2598 } else
2599 {
2600 {
2601 IkReal j5array[1], cj5array[1], sj5array[1];
2602 bool j5valid[1]={false};
2603 _nj5 = 1;
2604 IkReal x190=cj3*cj3;
2605 IkReal x191=(cj3*new_r22);
2606 CheckValue<IkReal> x192=IKPowWithIntegerCheck(IKsign(((-1.0)+(((-1.0)*x190*(new_r22*new_r22)))+x190)),-1);
2607 if(!x192.valid){
2608 continue;
2609 }
2610 CheckValue<IkReal> x193 = IKatan2WithCheck(IkReal((((new_r01*x191))+((new_r00*sj3)))),IkReal((((new_r01*sj3))+(((-1.0)*new_r00*x191)))),IKFAST_ATAN2_MAGTHRESH);
2611 if(!x193.valid){
2612 continue;
2613 }
2614 j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x192.value)))+(x193.value));
2615 sj5array[0]=IKsin(j5array[0]);
2616 cj5array[0]=IKcos(j5array[0]);
2617 if( j5array[0] > IKPI )
2618 {
2619  j5array[0]-=IK2PI;
2620 }
2621 else if( j5array[0] < -IKPI )
2622 { j5array[0]+=IK2PI;
2623 }
2624 j5valid[0] = true;
2625 for(int ij5 = 0; ij5 < 1; ++ij5)
2626 {
2627 if( !j5valid[ij5] )
2628 {
2629  continue;
2630 }
2631 _ij5[0] = ij5; _ij5[1] = -1;
2632 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2633 {
2634 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2635 {
2636  j5valid[iij5]=false; _ij5[1] = iij5; break;
2637 }
2638 }
2639 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2640 {
2641 IkReal evalcond[10];
2642 IkReal x194=IKsin(j5);
2643 IkReal x195=IKcos(j5);
2644 IkReal x196=((1.0)*new_r11);
2645 IkReal x197=(new_r22*sj3);
2646 IkReal x198=((1.0)*new_r10);
2647 IkReal x199=((1.0)*cj3*new_r22);
2648 IkReal x200=(sj3*x194);
2649 IkReal x201=(new_r22*x194);
2650 IkReal x202=((1.0)*x195);
2651 IkReal x203=((1.0)*x194);
2652 evalcond[0]=(((new_r00*sj3))+x194+(((-1.0)*cj3*x198)));
2653 evalcond[1]=(((new_r01*sj3))+x195+(((-1.0)*cj3*x196)));
2654 evalcond[2]=(((new_r11*sj3))+x201+((cj3*new_r01)));
2655 evalcond[3]=(((sj3*x195))+((cj3*x201))+new_r01);
2656 evalcond[4]=((((-1.0)*new_r22*x202))+((new_r10*sj3))+((cj3*new_r00)));
2657 evalcond[5]=((((-1.0)*x195*x199))+x200+new_r00);
2658 evalcond[6]=(((x194*x197))+new_r11+(((-1.0)*cj3*x202)));
2659 evalcond[7]=((((-1.0)*x197*x198))+x195+(((-1.0)*new_r00*x199)));
2660 evalcond[8]=((((-1.0)*x197*x202))+new_r10+(((-1.0)*cj3*x203)));
2661 evalcond[9]=((((-1.0)*x196*x197))+(((-1.0)*x203))+(((-1.0)*new_r01*x199)));
2662 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
2663 {
2664 continue;
2665 }
2666 }
2667 
2668 {
2669 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2670 vinfos[0].jointtype = 1;
2671 vinfos[0].foffset = j0;
2672 vinfos[0].indices[0] = _ij0[0];
2673 vinfos[0].indices[1] = _ij0[1];
2674 vinfos[0].maxsolutions = _nj0;
2675 vinfos[1].jointtype = 1;
2676 vinfos[1].foffset = j1;
2677 vinfos[1].indices[0] = _ij1[0];
2678 vinfos[1].indices[1] = _ij1[1];
2679 vinfos[1].maxsolutions = _nj1;
2680 vinfos[2].jointtype = 1;
2681 vinfos[2].foffset = j2;
2682 vinfos[2].indices[0] = _ij2[0];
2683 vinfos[2].indices[1] = _ij2[1];
2684 vinfos[2].maxsolutions = _nj2;
2685 vinfos[3].jointtype = 1;
2686 vinfos[3].foffset = j3;
2687 vinfos[3].indices[0] = _ij3[0];
2688 vinfos[3].indices[1] = _ij3[1];
2689 vinfos[3].maxsolutions = _nj3;
2690 vinfos[4].jointtype = 1;
2691 vinfos[4].foffset = j4;
2692 vinfos[4].indices[0] = _ij4[0];
2693 vinfos[4].indices[1] = _ij4[1];
2694 vinfos[4].maxsolutions = _nj4;
2695 vinfos[5].jointtype = 1;
2696 vinfos[5].foffset = j5;
2697 vinfos[5].indices[0] = _ij5[0];
2698 vinfos[5].indices[1] = _ij5[1];
2699 vinfos[5].maxsolutions = _nj5;
2700 std::vector<int> vfree(0);
2701 solutions.AddSolution(vinfos,vfree);
2702 }
2703 }
2704 }
2705 
2706 }
2707 
2708 }
2709  }
2710 
2711 }
2712 
2713 }
2714 
2715 }
2716 } while(0);
2717 if( bgotonextstatement )
2718 {
2719 bool bgotonextstatement = true;
2720 do
2721 {
2722 if( 1 )
2723 {
2724 bgotonextstatement=false;
2725 continue; // branch miss [j3, j5]
2726 
2727 }
2728 } while(0);
2729 if( bgotonextstatement )
2730 {
2731 }
2732 }
2733 }
2734 }
2735 }
2736 
2737 } else
2738 {
2739 {
2740 IkReal j3array[1], cj3array[1], sj3array[1];
2741 bool j3valid[1]={false};
2742 _nj3 = 1;
2744 if(!x205.valid){
2745 continue;
2746 }
2747 IkReal x204=x205.value;
2748 CheckValue<IkReal> x206=IKPowWithIntegerCheck(new_r12,-1);
2749 if(!x206.valid){
2750 continue;
2751 }
2752 if( IKabs((x204*(x206.value)*(((-1.0)+(new_r02*new_r02)+(cj4*cj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r02*x204)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x204*(x206.value)*(((-1.0)+(new_r02*new_r02)+(cj4*cj4)))))+IKsqr(((-1.0)*new_r02*x204))-1) <= IKFAST_SINCOS_THRESH )
2753  continue;
2754 j3array[0]=IKatan2((x204*(x206.value)*(((-1.0)+(new_r02*new_r02)+(cj4*cj4)))), ((-1.0)*new_r02*x204));
2755 sj3array[0]=IKsin(j3array[0]);
2756 cj3array[0]=IKcos(j3array[0]);
2757 if( j3array[0] > IKPI )
2758 {
2759  j3array[0]-=IK2PI;
2760 }
2761 else if( j3array[0] < -IKPI )
2762 { j3array[0]+=IK2PI;
2763 }
2764 j3valid[0] = true;
2765 for(int ij3 = 0; ij3 < 1; ++ij3)
2766 {
2767 if( !j3valid[ij3] )
2768 {
2769  continue;
2770 }
2771 _ij3[0] = ij3; _ij3[1] = -1;
2772 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2773 {
2774 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2775 {
2776  j3valid[iij3]=false; _ij3[1] = iij3; break;
2777 }
2778 }
2779 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2780 {
2781 IkReal evalcond[8];
2782 IkReal x207=IKcos(j3);
2783 IkReal x208=IKsin(j3);
2784 IkReal x209=((1.0)*cj4);
2785 IkReal x210=(sj4*x208);
2786 IkReal x211=(new_r12*x208);
2787 IkReal x212=(sj4*x207);
2788 IkReal x213=(new_r02*x207);
2789 evalcond[0]=(x212+new_r02);
2790 evalcond[1]=(x210+new_r12);
2791 evalcond[2]=((((-1.0)*new_r02*x208))+((new_r12*x207)));
2792 evalcond[3]=(sj4+x211+x213);
2793 evalcond[4]=((((-1.0)*new_r20*x209))+((new_r00*x212))+((new_r10*x210)));
2794 evalcond[5]=((((-1.0)*new_r21*x209))+((new_r01*x212))+((new_r11*x210)));
2795 evalcond[6]=((1.0)+(((-1.0)*new_r22*x209))+((new_r02*x212))+((new_r12*x210)));
2796 evalcond[7]=((((-1.0)*new_r22*sj4))+(((-1.0)*x209*x213))+(((-1.0)*x209*x211)));
2797 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
2798 {
2799 continue;
2800 }
2801 }
2802 
2803 {
2804 IkReal j5eval[3];
2805 j5eval[0]=sj4;
2806 j5eval[1]=IKsign(sj4);
2807 j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21)));
2808 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
2809 {
2810 {
2811 IkReal j5eval[2];
2812 j5eval[0]=sj4;
2813 j5eval[1]=sj3;
2814 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
2815 {
2816 {
2817 IkReal j5eval[2];
2818 j5eval[0]=sj4;
2819 j5eval[1]=cj3;
2820 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
2821 {
2822 {
2823 IkReal evalcond[5];
2824 bool bgotonextstatement = true;
2825 do
2826 {
2827 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959)));
2828 evalcond[1]=new_r02;
2829 evalcond[2]=new_r12;
2830 evalcond[3]=new_r21;
2831 evalcond[4]=new_r20;
2832 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
2833 {
2834 bgotonextstatement=false;
2835 {
2836 IkReal j5array[1], cj5array[1], sj5array[1];
2837 bool j5valid[1]={false};
2838 _nj5 = 1;
2839 IkReal x214=((1.0)*new_r01);
2840 if( IKabs(((((-1.0)*cj3*x214))+(((-1.0)*new_r00*sj3)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*sj3*x214))+((cj3*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*cj3*x214))+(((-1.0)*new_r00*sj3))))+IKsqr(((((-1.0)*sj3*x214))+((cj3*new_r00))))-1) <= IKFAST_SINCOS_THRESH )
2841  continue;
2842 j5array[0]=IKatan2(((((-1.0)*cj3*x214))+(((-1.0)*new_r00*sj3))), ((((-1.0)*sj3*x214))+((cj3*new_r00))));
2843 sj5array[0]=IKsin(j5array[0]);
2844 cj5array[0]=IKcos(j5array[0]);
2845 if( j5array[0] > IKPI )
2846 {
2847  j5array[0]-=IK2PI;
2848 }
2849 else if( j5array[0] < -IKPI )
2850 { j5array[0]+=IK2PI;
2851 }
2852 j5valid[0] = true;
2853 for(int ij5 = 0; ij5 < 1; ++ij5)
2854 {
2855 if( !j5valid[ij5] )
2856 {
2857  continue;
2858 }
2859 _ij5[0] = ij5; _ij5[1] = -1;
2860 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2861 {
2862 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2863 {
2864  j5valid[iij5]=false; _ij5[1] = iij5; break;
2865 }
2866 }
2867 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2868 {
2869 IkReal evalcond[8];
2870 IkReal x215=IKsin(j5);
2871 IkReal x216=IKcos(j5);
2872 IkReal x217=((1.0)*cj3);
2873 IkReal x218=(sj3*x215);
2874 IkReal x219=((1.0)*x216);
2875 IkReal x220=(x216*x217);
2876 evalcond[0]=(((new_r11*sj3))+x215+((cj3*new_r01)));
2877 evalcond[1]=(((new_r00*sj3))+(((-1.0)*new_r10*x217))+x215);
2878 evalcond[2]=((((-1.0)*new_r11*x217))+((new_r01*sj3))+x216);
2879 evalcond[3]=(((sj3*x216))+((cj3*x215))+new_r01);
2880 evalcond[4]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x219)));
2881 evalcond[5]=(x218+new_r00+(((-1.0)*x220)));
2882 evalcond[6]=(x218+new_r11+(((-1.0)*x220)));
2883 evalcond[7]=((((-1.0)*sj3*x219))+new_r10+(((-1.0)*x215*x217)));
2884 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
2885 {
2886 continue;
2887 }
2888 }
2889 
2890 {
2891 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2892 vinfos[0].jointtype = 1;
2893 vinfos[0].foffset = j0;
2894 vinfos[0].indices[0] = _ij0[0];
2895 vinfos[0].indices[1] = _ij0[1];
2896 vinfos[0].maxsolutions = _nj0;
2897 vinfos[1].jointtype = 1;
2898 vinfos[1].foffset = j1;
2899 vinfos[1].indices[0] = _ij1[0];
2900 vinfos[1].indices[1] = _ij1[1];
2901 vinfos[1].maxsolutions = _nj1;
2902 vinfos[2].jointtype = 1;
2903 vinfos[2].foffset = j2;
2904 vinfos[2].indices[0] = _ij2[0];
2905 vinfos[2].indices[1] = _ij2[1];
2906 vinfos[2].maxsolutions = _nj2;
2907 vinfos[3].jointtype = 1;
2908 vinfos[3].foffset = j3;
2909 vinfos[3].indices[0] = _ij3[0];
2910 vinfos[3].indices[1] = _ij3[1];
2911 vinfos[3].maxsolutions = _nj3;
2912 vinfos[4].jointtype = 1;
2913 vinfos[4].foffset = j4;
2914 vinfos[4].indices[0] = _ij4[0];
2915 vinfos[4].indices[1] = _ij4[1];
2916 vinfos[4].maxsolutions = _nj4;
2917 vinfos[5].jointtype = 1;
2918 vinfos[5].foffset = j5;
2919 vinfos[5].indices[0] = _ij5[0];
2920 vinfos[5].indices[1] = _ij5[1];
2921 vinfos[5].maxsolutions = _nj5;
2922 std::vector<int> vfree(0);
2923 solutions.AddSolution(vinfos,vfree);
2924 }
2925 }
2926 }
2927 
2928 }
2929 } while(0);
2930 if( bgotonextstatement )
2931 {
2932 bool bgotonextstatement = true;
2933 do
2934 {
2935 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959)));
2936 evalcond[1]=new_r02;
2937 evalcond[2]=new_r12;
2938 evalcond[3]=new_r21;
2939 evalcond[4]=new_r20;
2940 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
2941 {
2942 bgotonextstatement=false;
2943 {
2944 IkReal j5array[1], cj5array[1], sj5array[1];
2945 bool j5valid[1]={false};
2946 _nj5 = 1;
2947 IkReal x221=((1.0)*sj3);
2948 if( IKabs((((cj3*new_r01))+(((-1.0)*new_r00*x221)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r01*x221))+(((-1.0)*cj3*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((cj3*new_r01))+(((-1.0)*new_r00*x221))))+IKsqr(((((-1.0)*new_r01*x221))+(((-1.0)*cj3*new_r00))))-1) <= IKFAST_SINCOS_THRESH )
2949  continue;
2950 j5array[0]=IKatan2((((cj3*new_r01))+(((-1.0)*new_r00*x221))), ((((-1.0)*new_r01*x221))+(((-1.0)*cj3*new_r00))));
2951 sj5array[0]=IKsin(j5array[0]);
2952 cj5array[0]=IKcos(j5array[0]);
2953 if( j5array[0] > IKPI )
2954 {
2955  j5array[0]-=IK2PI;
2956 }
2957 else if( j5array[0] < -IKPI )
2958 { j5array[0]+=IK2PI;
2959 }
2960 j5valid[0] = true;
2961 for(int ij5 = 0; ij5 < 1; ++ij5)
2962 {
2963 if( !j5valid[ij5] )
2964 {
2965  continue;
2966 }
2967 _ij5[0] = ij5; _ij5[1] = -1;
2968 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2969 {
2970 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2971 {
2972  j5valid[iij5]=false; _ij5[1] = iij5; break;
2973 }
2974 }
2975 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2976 {
2977 IkReal evalcond[8];
2978 IkReal x222=IKcos(j5);
2979 IkReal x223=IKsin(j5);
2980 IkReal x224=((1.0)*cj3);
2981 IkReal x225=(sj3*x222);
2982 IkReal x226=((1.0)*x223);
2983 IkReal x227=(x223*x224);
2984 evalcond[0]=(((new_r10*sj3))+x222+((cj3*new_r00)));
2985 evalcond[1]=((((-1.0)*new_r10*x224))+((new_r00*sj3))+x223);
2986 evalcond[2]=((((-1.0)*new_r11*x224))+((new_r01*sj3))+x222);
2987 evalcond[3]=(((new_r11*sj3))+((cj3*new_r01))+(((-1.0)*x226)));
2988 evalcond[4]=(((cj3*x222))+((sj3*x223))+new_r00);
2989 evalcond[5]=(x225+new_r01+(((-1.0)*x227)));
2990 evalcond[6]=(x225+new_r10+(((-1.0)*x227)));
2991 evalcond[7]=((((-1.0)*x222*x224))+(((-1.0)*sj3*x226))+new_r11);
2992 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
2993 {
2994 continue;
2995 }
2996 }
2997 
2998 {
2999 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3000 vinfos[0].jointtype = 1;
3001 vinfos[0].foffset = j0;
3002 vinfos[0].indices[0] = _ij0[0];
3003 vinfos[0].indices[1] = _ij0[1];
3004 vinfos[0].maxsolutions = _nj0;
3005 vinfos[1].jointtype = 1;
3006 vinfos[1].foffset = j1;
3007 vinfos[1].indices[0] = _ij1[0];
3008 vinfos[1].indices[1] = _ij1[1];
3009 vinfos[1].maxsolutions = _nj1;
3010 vinfos[2].jointtype = 1;
3011 vinfos[2].foffset = j2;
3012 vinfos[2].indices[0] = _ij2[0];
3013 vinfos[2].indices[1] = _ij2[1];
3014 vinfos[2].maxsolutions = _nj2;
3015 vinfos[3].jointtype = 1;
3016 vinfos[3].foffset = j3;
3017 vinfos[3].indices[0] = _ij3[0];
3018 vinfos[3].indices[1] = _ij3[1];
3019 vinfos[3].maxsolutions = _nj3;
3020 vinfos[4].jointtype = 1;
3021 vinfos[4].foffset = j4;
3022 vinfos[4].indices[0] = _ij4[0];
3023 vinfos[4].indices[1] = _ij4[1];
3024 vinfos[4].maxsolutions = _nj4;
3025 vinfos[5].jointtype = 1;
3026 vinfos[5].foffset = j5;
3027 vinfos[5].indices[0] = _ij5[0];
3028 vinfos[5].indices[1] = _ij5[1];
3029 vinfos[5].maxsolutions = _nj5;
3030 std::vector<int> vfree(0);
3031 solutions.AddSolution(vinfos,vfree);
3032 }
3033 }
3034 }
3035 
3036 }
3037 } while(0);
3038 if( bgotonextstatement )
3039 {
3040 bool bgotonextstatement = true;
3041 do
3042 {
3043 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959)));
3044 evalcond[1]=new_r02;
3045 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
3046 {
3047 bgotonextstatement=false;
3048 {
3049 IkReal j5array[1], cj5array[1], sj5array[1];
3050 bool j5valid[1]={false};
3051 _nj5 = 1;
3052 if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(((-1.0)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
3053  continue;
3054 j5array[0]=IKatan2(((-1.0)*new_r00), ((-1.0)*new_r01));
3055 sj5array[0]=IKsin(j5array[0]);
3056 cj5array[0]=IKcos(j5array[0]);
3057 if( j5array[0] > IKPI )
3058 {
3059  j5array[0]-=IK2PI;
3060 }
3061 else if( j5array[0] < -IKPI )
3062 { j5array[0]+=IK2PI;
3063 }
3064 j5valid[0] = true;
3065 for(int ij5 = 0; ij5 < 1; ++ij5)
3066 {
3067 if( !j5valid[ij5] )
3068 {
3069  continue;
3070 }
3071 _ij5[0] = ij5; _ij5[1] = -1;
3072 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3073 {
3074 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3075 {
3076  j5valid[iij5]=false; _ij5[1] = iij5; break;
3077 }
3078 }
3079 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3080 {
3081 IkReal evalcond[8];
3082 IkReal x228=IKsin(j5);
3083 IkReal x229=IKcos(j5);
3084 IkReal x230=((1.0)*cj4);
3085 IkReal x231=((1.0)*sj4);
3086 evalcond[0]=(x228+new_r00);
3087 evalcond[1]=(x229+new_r01);
3088 evalcond[2]=(((sj4*x228))+new_r21);
3089 evalcond[3]=(((cj4*x228))+new_r11);
3090 evalcond[4]=(new_r20+(((-1.0)*x229*x231)));
3091 evalcond[5]=(new_r10+(((-1.0)*x229*x230)));
3092 evalcond[6]=((((-1.0)*new_r20*x231))+x229+(((-1.0)*new_r10*x230)));
3093 evalcond[7]=((((-1.0)*new_r21*x231))+(((-1.0)*new_r11*x230))+(((-1.0)*x228)));
3094 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
3095 {
3096 continue;
3097 }
3098 }
3099 
3100 {
3101 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3102 vinfos[0].jointtype = 1;
3103 vinfos[0].foffset = j0;
3104 vinfos[0].indices[0] = _ij0[0];
3105 vinfos[0].indices[1] = _ij0[1];
3106 vinfos[0].maxsolutions = _nj0;
3107 vinfos[1].jointtype = 1;
3108 vinfos[1].foffset = j1;
3109 vinfos[1].indices[0] = _ij1[0];
3110 vinfos[1].indices[1] = _ij1[1];
3111 vinfos[1].maxsolutions = _nj1;
3112 vinfos[2].jointtype = 1;
3113 vinfos[2].foffset = j2;
3114 vinfos[2].indices[0] = _ij2[0];
3115 vinfos[2].indices[1] = _ij2[1];
3116 vinfos[2].maxsolutions = _nj2;
3117 vinfos[3].jointtype = 1;
3118 vinfos[3].foffset = j3;
3119 vinfos[3].indices[0] = _ij3[0];
3120 vinfos[3].indices[1] = _ij3[1];
3121 vinfos[3].maxsolutions = _nj3;
3122 vinfos[4].jointtype = 1;
3123 vinfos[4].foffset = j4;
3124 vinfos[4].indices[0] = _ij4[0];
3125 vinfos[4].indices[1] = _ij4[1];
3126 vinfos[4].maxsolutions = _nj4;
3127 vinfos[5].jointtype = 1;
3128 vinfos[5].foffset = j5;
3129 vinfos[5].indices[0] = _ij5[0];
3130 vinfos[5].indices[1] = _ij5[1];
3131 vinfos[5].maxsolutions = _nj5;
3132 std::vector<int> vfree(0);
3133 solutions.AddSolution(vinfos,vfree);
3134 }
3135 }
3136 }
3137 
3138 }
3139 } while(0);
3140 if( bgotonextstatement )
3141 {
3142 bool bgotonextstatement = true;
3143 do
3144 {
3145 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959)));
3146 evalcond[1]=new_r02;
3147 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
3148 {
3149 bgotonextstatement=false;
3150 {
3151 IkReal j5array[1], cj5array[1], sj5array[1];
3152 bool j5valid[1]={false};
3153 _nj5 = 1;
3154 if( IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r00)+IKsqr(new_r01)-1) <= IKFAST_SINCOS_THRESH )
3155  continue;
3156 j5array[0]=IKatan2(new_r00, new_r01);
3157 sj5array[0]=IKsin(j5array[0]);
3158 cj5array[0]=IKcos(j5array[0]);
3159 if( j5array[0] > IKPI )
3160 {
3161  j5array[0]-=IK2PI;
3162 }
3163 else if( j5array[0] < -IKPI )
3164 { j5array[0]+=IK2PI;
3165 }
3166 j5valid[0] = true;
3167 for(int ij5 = 0; ij5 < 1; ++ij5)
3168 {
3169 if( !j5valid[ij5] )
3170 {
3171  continue;
3172 }
3173 _ij5[0] = ij5; _ij5[1] = -1;
3174 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3175 {
3176 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3177 {
3178  j5valid[iij5]=false; _ij5[1] = iij5; break;
3179 }
3180 }
3181 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3182 {
3183 IkReal evalcond[8];
3184 IkReal x232=IKsin(j5);
3185 IkReal x233=IKcos(j5);
3186 IkReal x234=((1.0)*sj4);
3187 IkReal x235=((1.0)*x233);
3188 evalcond[0]=(((sj4*x232))+new_r21);
3189 evalcond[1]=(x232+(((-1.0)*new_r00)));
3190 evalcond[2]=(x233+(((-1.0)*new_r01)));
3191 evalcond[3]=((((-1.0)*x233*x234))+new_r20);
3192 evalcond[4]=(((cj4*x232))+(((-1.0)*new_r11)));
3193 evalcond[5]=((((-1.0)*cj4*x235))+(((-1.0)*new_r10)));
3194 evalcond[6]=((((-1.0)*new_r20*x234))+((cj4*new_r10))+x233);
3195 evalcond[7]=((((-1.0)*new_r21*x234))+((cj4*new_r11))+(((-1.0)*x232)));
3196 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
3197 {
3198 continue;
3199 }
3200 }
3201 
3202 {
3203 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3204 vinfos[0].jointtype = 1;
3205 vinfos[0].foffset = j0;
3206 vinfos[0].indices[0] = _ij0[0];
3207 vinfos[0].indices[1] = _ij0[1];
3208 vinfos[0].maxsolutions = _nj0;
3209 vinfos[1].jointtype = 1;
3210 vinfos[1].foffset = j1;
3211 vinfos[1].indices[0] = _ij1[0];
3212 vinfos[1].indices[1] = _ij1[1];
3213 vinfos[1].maxsolutions = _nj1;
3214 vinfos[2].jointtype = 1;
3215 vinfos[2].foffset = j2;
3216 vinfos[2].indices[0] = _ij2[0];
3217 vinfos[2].indices[1] = _ij2[1];
3218 vinfos[2].maxsolutions = _nj2;
3219 vinfos[3].jointtype = 1;
3220 vinfos[3].foffset = j3;
3221 vinfos[3].indices[0] = _ij3[0];
3222 vinfos[3].indices[1] = _ij3[1];
3223 vinfos[3].maxsolutions = _nj3;
3224 vinfos[4].jointtype = 1;
3225 vinfos[4].foffset = j4;
3226 vinfos[4].indices[0] = _ij4[0];
3227 vinfos[4].indices[1] = _ij4[1];
3228 vinfos[4].maxsolutions = _nj4;
3229 vinfos[5].jointtype = 1;
3230 vinfos[5].foffset = j5;
3231 vinfos[5].indices[0] = _ij5[0];
3232 vinfos[5].indices[1] = _ij5[1];
3233 vinfos[5].maxsolutions = _nj5;
3234 std::vector<int> vfree(0);
3235 solutions.AddSolution(vinfos,vfree);
3236 }
3237 }
3238 }
3239 
3240 }
3241 } while(0);
3242 if( bgotonextstatement )
3243 {
3244 bool bgotonextstatement = true;
3245 do
3246 {
3247 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j3))), 6.28318530717959)));
3248 evalcond[1]=new_r12;
3249 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
3250 {
3251 bgotonextstatement=false;
3252 {
3253 IkReal j5array[1], cj5array[1], sj5array[1];
3254 bool j5valid[1]={false};
3255 _nj5 = 1;
3256 if( IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r10)+IKsqr(new_r11)-1) <= IKFAST_SINCOS_THRESH )
3257  continue;
3258 j5array[0]=IKatan2(new_r10, new_r11);
3259 sj5array[0]=IKsin(j5array[0]);
3260 cj5array[0]=IKcos(j5array[0]);
3261 if( j5array[0] > IKPI )
3262 {
3263  j5array[0]-=IK2PI;
3264 }
3265 else if( j5array[0] < -IKPI )
3266 { j5array[0]+=IK2PI;
3267 }
3268 j5valid[0] = true;
3269 for(int ij5 = 0; ij5 < 1; ++ij5)
3270 {
3271 if( !j5valid[ij5] )
3272 {
3273  continue;
3274 }
3275 _ij5[0] = ij5; _ij5[1] = -1;
3276 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3277 {
3278 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3279 {
3280  j5valid[iij5]=false; _ij5[1] = iij5; break;
3281 }
3282 }
3283 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3284 {
3285 IkReal evalcond[8];
3286 IkReal x236=IKcos(j5);
3287 IkReal x237=IKsin(j5);
3288 IkReal x238=((1.0)*cj4);
3289 IkReal x239=((1.0)*sj4);
3290 IkReal x240=((1.0)*x237);
3291 evalcond[0]=(((new_r02*x236))+new_r20);
3292 evalcond[1]=(x237+(((-1.0)*new_r10)));
3293 evalcond[2]=(x236+(((-1.0)*new_r11)));
3294 evalcond[3]=(((cj4*x237))+new_r01);
3295 evalcond[4]=((((-1.0)*new_r02*x240))+new_r21);
3296 evalcond[5]=((((-1.0)*x236*x238))+new_r00);
3297 evalcond[6]=((((-1.0)*new_r20*x239))+x236+(((-1.0)*new_r00*x238)));
3298 evalcond[7]=((((-1.0)*new_r21*x239))+(((-1.0)*x240))+(((-1.0)*new_r01*x238)));
3299 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
3300 {
3301 continue;
3302 }
3303 }
3304 
3305 {
3306 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3307 vinfos[0].jointtype = 1;
3308 vinfos[0].foffset = j0;
3309 vinfos[0].indices[0] = _ij0[0];
3310 vinfos[0].indices[1] = _ij0[1];
3311 vinfos[0].maxsolutions = _nj0;
3312 vinfos[1].jointtype = 1;
3313 vinfos[1].foffset = j1;
3314 vinfos[1].indices[0] = _ij1[0];
3315 vinfos[1].indices[1] = _ij1[1];
3316 vinfos[1].maxsolutions = _nj1;
3317 vinfos[2].jointtype = 1;
3318 vinfos[2].foffset = j2;
3319 vinfos[2].indices[0] = _ij2[0];
3320 vinfos[2].indices[1] = _ij2[1];
3321 vinfos[2].maxsolutions = _nj2;
3322 vinfos[3].jointtype = 1;
3323 vinfos[3].foffset = j3;
3324 vinfos[3].indices[0] = _ij3[0];
3325 vinfos[3].indices[1] = _ij3[1];
3326 vinfos[3].maxsolutions = _nj3;
3327 vinfos[4].jointtype = 1;
3328 vinfos[4].foffset = j4;
3329 vinfos[4].indices[0] = _ij4[0];
3330 vinfos[4].indices[1] = _ij4[1];
3331 vinfos[4].maxsolutions = _nj4;
3332 vinfos[5].jointtype = 1;
3333 vinfos[5].foffset = j5;
3334 vinfos[5].indices[0] = _ij5[0];
3335 vinfos[5].indices[1] = _ij5[1];
3336 vinfos[5].maxsolutions = _nj5;
3337 std::vector<int> vfree(0);
3338 solutions.AddSolution(vinfos,vfree);
3339 }
3340 }
3341 }
3342 
3343 }
3344 } while(0);
3345 if( bgotonextstatement )
3346 {
3347 bool bgotonextstatement = true;
3348 do
3349 {
3350 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j3)))), 6.28318530717959)));
3351 evalcond[1]=new_r12;
3352 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
3353 {
3354 bgotonextstatement=false;
3355 {
3356 IkReal j5array[1], cj5array[1], sj5array[1];
3357 bool j5valid[1]={false};
3358 _nj5 = 1;
3359 if( IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r10))+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH )
3360  continue;
3361 j5array[0]=IKatan2(((-1.0)*new_r10), ((-1.0)*new_r11));
3362 sj5array[0]=IKsin(j5array[0]);
3363 cj5array[0]=IKcos(j5array[0]);
3364 if( j5array[0] > IKPI )
3365 {
3366  j5array[0]-=IK2PI;
3367 }
3368 else if( j5array[0] < -IKPI )
3369 { j5array[0]+=IK2PI;
3370 }
3371 j5valid[0] = true;
3372 for(int ij5 = 0; ij5 < 1; ++ij5)
3373 {
3374 if( !j5valid[ij5] )
3375 {
3376  continue;
3377 }
3378 _ij5[0] = ij5; _ij5[1] = -1;
3379 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3380 {
3381 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3382 {
3383  j5valid[iij5]=false; _ij5[1] = iij5; break;
3384 }
3385 }
3386 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3387 {
3388 IkReal evalcond[8];
3389 IkReal x241=IKsin(j5);
3390 IkReal x242=IKcos(j5);
3391 IkReal x243=((1.0)*sj4);
3392 IkReal x244=((1.0)*x242);
3393 evalcond[0]=(x241+new_r10);
3394 evalcond[1]=(x242+new_r11);
3395 evalcond[2]=(new_r21+((new_r02*x241)));
3396 evalcond[3]=((((-1.0)*new_r02*x244))+new_r20);
3397 evalcond[4]=(((cj4*x241))+(((-1.0)*new_r01)));
3398 evalcond[5]=((((-1.0)*cj4*x244))+(((-1.0)*new_r00)));
3399 evalcond[6]=(((cj4*new_r00))+x242+(((-1.0)*new_r20*x243)));
3400 evalcond[7]=(((cj4*new_r01))+(((-1.0)*x241))+(((-1.0)*new_r21*x243)));
3401 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
3402 {
3403 continue;
3404 }
3405 }
3406 
3407 {
3408 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3409 vinfos[0].jointtype = 1;
3410 vinfos[0].foffset = j0;
3411 vinfos[0].indices[0] = _ij0[0];
3412 vinfos[0].indices[1] = _ij0[1];
3413 vinfos[0].maxsolutions = _nj0;
3414 vinfos[1].jointtype = 1;
3415 vinfos[1].foffset = j1;
3416 vinfos[1].indices[0] = _ij1[0];
3417 vinfos[1].indices[1] = _ij1[1];
3418 vinfos[1].maxsolutions = _nj1;
3419 vinfos[2].jointtype = 1;
3420 vinfos[2].foffset = j2;
3421 vinfos[2].indices[0] = _ij2[0];
3422 vinfos[2].indices[1] = _ij2[1];
3423 vinfos[2].maxsolutions = _nj2;
3424 vinfos[3].jointtype = 1;
3425 vinfos[3].foffset = j3;
3426 vinfos[3].indices[0] = _ij3[0];
3427 vinfos[3].indices[1] = _ij3[1];
3428 vinfos[3].maxsolutions = _nj3;
3429 vinfos[4].jointtype = 1;
3430 vinfos[4].foffset = j4;
3431 vinfos[4].indices[0] = _ij4[0];
3432 vinfos[4].indices[1] = _ij4[1];
3433 vinfos[4].maxsolutions = _nj4;
3434 vinfos[5].jointtype = 1;
3435 vinfos[5].foffset = j5;
3436 vinfos[5].indices[0] = _ij5[0];
3437 vinfos[5].indices[1] = _ij5[1];
3438 vinfos[5].maxsolutions = _nj5;
3439 std::vector<int> vfree(0);
3440 solutions.AddSolution(vinfos,vfree);
3441 }
3442 }
3443 }
3444 
3445 }
3446 } while(0);
3447 if( bgotonextstatement )
3448 {
3449 bool bgotonextstatement = true;
3450 do
3451 {
3452 evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21)));
3453 if( IKabs(evalcond[0]) < 0.0000050000000000 )
3454 {
3455 bgotonextstatement=false;
3456 {
3457 IkReal j5eval[1];
3458 new_r21=0;
3459 new_r20=0;
3460 new_r02=0;
3461 new_r12=0;
3462 j5eval[0]=1.0;
3463 if( IKabs(j5eval[0]) < 0.0000000100000000 )
3464 {
3465 continue; // no branches [j5]
3466 
3467 } else
3468 {
3469 IkReal op[2+1], zeror[2];
3470 int numroots;
3471 op[0]=-1.0;
3472 op[1]=0;
3473 op[2]=1.0;
3474 polyroots2(op,zeror,numroots);
3475 IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
3476 int numsolutions = 0;
3477 for(int ij5 = 0; ij5 < numroots; ++ij5)
3478 {
3479 IkReal htj5 = zeror[ij5];
3480 tempj5array[0]=((2.0)*(atan(htj5)));
3481 for(int kj5 = 0; kj5 < 1; ++kj5)
3482 {
3483 j5array[numsolutions] = tempj5array[kj5];
3484 if( j5array[numsolutions] > IKPI )
3485 {
3486  j5array[numsolutions]-=IK2PI;
3487 }
3488 else if( j5array[numsolutions] < -IKPI )
3489 {
3490  j5array[numsolutions]+=IK2PI;
3491 }
3492 sj5array[numsolutions] = IKsin(j5array[numsolutions]);
3493 cj5array[numsolutions] = IKcos(j5array[numsolutions]);
3494 numsolutions++;
3495 }
3496 }
3497 bool j5valid[2]={true,true};
3498 _nj5 = 2;
3499 for(int ij5 = 0; ij5 < numsolutions; ++ij5)
3500  {
3501 if( !j5valid[ij5] )
3502 {
3503  continue;
3504 }
3505  j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3506 htj5 = IKtan(j5/2);
3507 
3508 _ij5[0] = ij5; _ij5[1] = -1;
3509 for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
3510 {
3511 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3512 {
3513  j5valid[iij5]=false; _ij5[1] = iij5; break;
3514 }
3515 }
3516 {
3517 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3518 vinfos[0].jointtype = 1;
3519 vinfos[0].foffset = j0;
3520 vinfos[0].indices[0] = _ij0[0];
3521 vinfos[0].indices[1] = _ij0[1];
3522 vinfos[0].maxsolutions = _nj0;
3523 vinfos[1].jointtype = 1;
3524 vinfos[1].foffset = j1;
3525 vinfos[1].indices[0] = _ij1[0];
3526 vinfos[1].indices[1] = _ij1[1];
3527 vinfos[1].maxsolutions = _nj1;
3528 vinfos[2].jointtype = 1;
3529 vinfos[2].foffset = j2;
3530 vinfos[2].indices[0] = _ij2[0];
3531 vinfos[2].indices[1] = _ij2[1];
3532 vinfos[2].maxsolutions = _nj2;
3533 vinfos[3].jointtype = 1;
3534 vinfos[3].foffset = j3;
3535 vinfos[3].indices[0] = _ij3[0];
3536 vinfos[3].indices[1] = _ij3[1];
3537 vinfos[3].maxsolutions = _nj3;
3538 vinfos[4].jointtype = 1;
3539 vinfos[4].foffset = j4;
3540 vinfos[4].indices[0] = _ij4[0];
3541 vinfos[4].indices[1] = _ij4[1];
3542 vinfos[4].maxsolutions = _nj4;
3543 vinfos[5].jointtype = 1;
3544 vinfos[5].foffset = j5;
3545 vinfos[5].indices[0] = _ij5[0];
3546 vinfos[5].indices[1] = _ij5[1];
3547 vinfos[5].maxsolutions = _nj5;
3548 std::vector<int> vfree(0);
3549 solutions.AddSolution(vinfos,vfree);
3550 }
3551  }
3552 
3553 }
3554 
3555 }
3556 
3557 }
3558 } while(0);
3559 if( bgotonextstatement )
3560 {
3561 bool bgotonextstatement = true;
3562 do
3563 {
3564 if( 1 )
3565 {
3566 bgotonextstatement=false;
3567 continue; // branch miss [j5]
3568 
3569 }
3570 } while(0);
3571 if( bgotonextstatement )
3572 {
3573 }
3574 }
3575 }
3576 }
3577 }
3578 }
3579 }
3580 }
3581 }
3582 
3583 } else
3584 {
3585 {
3586 IkReal j5array[1], cj5array[1], sj5array[1];
3587 bool j5valid[1]={false};
3588 _nj5 = 1;
3590 if(!x246.valid){
3591 continue;
3592 }
3593 IkReal x245=x246.value;
3595 if(!x247.valid){
3596 continue;
3597 }
3598 if( IKabs(((-1.0)*new_r21*x245)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x245*(x247.value)*((((new_r11*sj4))+(((-1.0)*cj4*new_r21*sj3)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r21*x245))+IKsqr((x245*(x247.value)*((((new_r11*sj4))+(((-1.0)*cj4*new_r21*sj3))))))-1) <= IKFAST_SINCOS_THRESH )
3599  continue;
3600 j5array[0]=IKatan2(((-1.0)*new_r21*x245), (x245*(x247.value)*((((new_r11*sj4))+(((-1.0)*cj4*new_r21*sj3))))));
3601 sj5array[0]=IKsin(j5array[0]);
3602 cj5array[0]=IKcos(j5array[0]);
3603 if( j5array[0] > IKPI )
3604 {
3605  j5array[0]-=IK2PI;
3606 }
3607 else if( j5array[0] < -IKPI )
3608 { j5array[0]+=IK2PI;
3609 }
3610 j5valid[0] = true;
3611 for(int ij5 = 0; ij5 < 1; ++ij5)
3612 {
3613 if( !j5valid[ij5] )
3614 {
3615  continue;
3616 }
3617 _ij5[0] = ij5; _ij5[1] = -1;
3618 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3619 {
3620 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3621 {
3622  j5valid[iij5]=false; _ij5[1] = iij5; break;
3623 }
3624 }
3625 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3626 {
3627 IkReal evalcond[12];
3628 IkReal x248=IKsin(j5);
3629 IkReal x249=IKcos(j5);
3630 IkReal x250=(cj3*new_r00);
3631 IkReal x251=(cj3*cj4);
3632 IkReal x252=((1.0)*cj3);
3633 IkReal x253=(new_r11*sj3);
3634 IkReal x254=((1.0)*cj4);
3635 IkReal x255=(new_r10*sj3);
3636 IkReal x256=((1.0)*sj4);
3637 IkReal x257=(sj3*x248);
3638 IkReal x258=((1.0)*x249);
3639 IkReal x259=(sj3*x249);
3640 evalcond[0]=(new_r21+((sj4*x248)));
3641 evalcond[1]=((((-1.0)*x249*x256))+new_r20);
3642 evalcond[2]=((((-1.0)*new_r10*x252))+((new_r00*sj3))+x248);
3643 evalcond[3]=((((-1.0)*new_r11*x252))+((new_r01*sj3))+x249);
3644 evalcond[4]=(((cj4*x248))+x253+((cj3*new_r01)));
3645 evalcond[5]=(((x248*x251))+x259+new_r01);
3646 evalcond[6]=(x255+x250+(((-1.0)*x249*x254)));
3647 evalcond[7]=((((-1.0)*x251*x258))+x257+new_r00);
3648 evalcond[8]=((((-1.0)*x249*x252))+new_r11+((cj4*x257)));
3649 evalcond[9]=((((-1.0)*x254*x259))+(((-1.0)*x248*x252))+new_r10);
3650 evalcond[10]=((((-1.0)*x250*x254))+(((-1.0)*x254*x255))+x249+(((-1.0)*new_r20*x256)));
3651 evalcond[11]=((((-1.0)*new_r21*x256))+(((-1.0)*x248))+(((-1.0)*x253*x254))+(((-1.0)*new_r01*x251)));
3652 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
3653 {
3654 continue;
3655 }
3656 }
3657 
3658 {
3659 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3660 vinfos[0].jointtype = 1;
3661 vinfos[0].foffset = j0;
3662 vinfos[0].indices[0] = _ij0[0];
3663 vinfos[0].indices[1] = _ij0[1];
3664 vinfos[0].maxsolutions = _nj0;
3665 vinfos[1].jointtype = 1;
3666 vinfos[1].foffset = j1;
3667 vinfos[1].indices[0] = _ij1[0];
3668 vinfos[1].indices[1] = _ij1[1];
3669 vinfos[1].maxsolutions = _nj1;
3670 vinfos[2].jointtype = 1;
3671 vinfos[2].foffset = j2;
3672 vinfos[2].indices[0] = _ij2[0];
3673 vinfos[2].indices[1] = _ij2[1];
3674 vinfos[2].maxsolutions = _nj2;
3675 vinfos[3].jointtype = 1;
3676 vinfos[3].foffset = j3;
3677 vinfos[3].indices[0] = _ij3[0];
3678 vinfos[3].indices[1] = _ij3[1];
3679 vinfos[3].maxsolutions = _nj3;
3680 vinfos[4].jointtype = 1;
3681 vinfos[4].foffset = j4;
3682 vinfos[4].indices[0] = _ij4[0];
3683 vinfos[4].indices[1] = _ij4[1];
3684 vinfos[4].maxsolutions = _nj4;
3685 vinfos[5].jointtype = 1;
3686 vinfos[5].foffset = j5;
3687 vinfos[5].indices[0] = _ij5[0];
3688 vinfos[5].indices[1] = _ij5[1];
3689 vinfos[5].maxsolutions = _nj5;
3690 std::vector<int> vfree(0);
3691 solutions.AddSolution(vinfos,vfree);
3692 }
3693 }
3694 }
3695 
3696 }
3697 
3698 }
3699 
3700 } else
3701 {
3702 {
3703 IkReal j5array[1], cj5array[1], sj5array[1];
3704 bool j5valid[1]={false};
3705 _nj5 = 1;
3707 if(!x261.valid){
3708 continue;
3709 }
3710 IkReal x260=x261.value;
3712 if(!x262.valid){
3713 continue;
3714 }
3715 if( IKabs(((-1.0)*new_r21*x260)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x260*(x262.value)*(((((-1.0)*new_r01*sj4))+((cj3*cj4*new_r21)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r21*x260))+IKsqr((x260*(x262.value)*(((((-1.0)*new_r01*sj4))+((cj3*cj4*new_r21))))))-1) <= IKFAST_SINCOS_THRESH )
3716  continue;
3717 j5array[0]=IKatan2(((-1.0)*new_r21*x260), (x260*(x262.value)*(((((-1.0)*new_r01*sj4))+((cj3*cj4*new_r21))))));
3718 sj5array[0]=IKsin(j5array[0]);
3719 cj5array[0]=IKcos(j5array[0]);
3720 if( j5array[0] > IKPI )
3721 {
3722  j5array[0]-=IK2PI;
3723 }
3724 else if( j5array[0] < -IKPI )
3725 { j5array[0]+=IK2PI;
3726 }
3727 j5valid[0] = true;
3728 for(int ij5 = 0; ij5 < 1; ++ij5)
3729 {
3730 if( !j5valid[ij5] )
3731 {
3732  continue;
3733 }
3734 _ij5[0] = ij5; _ij5[1] = -1;
3735 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3736 {
3737 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3738 {
3739  j5valid[iij5]=false; _ij5[1] = iij5; break;
3740 }
3741 }
3742 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3743 {
3744 IkReal evalcond[12];
3745 IkReal x263=IKsin(j5);
3746 IkReal x264=IKcos(j5);
3747 IkReal x265=(cj3*new_r00);
3748 IkReal x266=(cj3*cj4);
3749 IkReal x267=((1.0)*cj3);
3750 IkReal x268=(new_r11*sj3);
3751 IkReal x269=((1.0)*cj4);
3752 IkReal x270=(new_r10*sj3);
3753 IkReal x271=((1.0)*sj4);
3754 IkReal x272=(sj3*x263);
3755 IkReal x273=((1.0)*x264);
3756 IkReal x274=(sj3*x264);
3757 evalcond[0]=(new_r21+((sj4*x263)));
3758 evalcond[1]=(new_r20+(((-1.0)*x264*x271)));
3759 evalcond[2]=(((new_r00*sj3))+x263+(((-1.0)*new_r10*x267)));
3760 evalcond[3]=(((new_r01*sj3))+x264+(((-1.0)*new_r11*x267)));
3761 evalcond[4]=(((cj4*x263))+x268+((cj3*new_r01)));
3762 evalcond[5]=(((x263*x266))+x274+new_r01);
3763 evalcond[6]=(x265+x270+(((-1.0)*x264*x269)));
3764 evalcond[7]=(x272+(((-1.0)*x266*x273))+new_r00);
3765 evalcond[8]=(((cj4*x272))+new_r11+(((-1.0)*x264*x267)));
3766 evalcond[9]=((((-1.0)*x263*x267))+(((-1.0)*x269*x274))+new_r10);
3767 evalcond[10]=((((-1.0)*x269*x270))+x264+(((-1.0)*new_r20*x271))+(((-1.0)*x265*x269)));
3768 evalcond[11]=((((-1.0)*x263))+(((-1.0)*new_r01*x266))+(((-1.0)*new_r21*x271))+(((-1.0)*x268*x269)));
3769 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
3770 {
3771 continue;
3772 }
3773 }
3774 
3775 {
3776 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3777 vinfos[0].jointtype = 1;
3778 vinfos[0].foffset = j0;
3779 vinfos[0].indices[0] = _ij0[0];
3780 vinfos[0].indices[1] = _ij0[1];
3781 vinfos[0].maxsolutions = _nj0;
3782 vinfos[1].jointtype = 1;
3783 vinfos[1].foffset = j1;
3784 vinfos[1].indices[0] = _ij1[0];
3785 vinfos[1].indices[1] = _ij1[1];
3786 vinfos[1].maxsolutions = _nj1;
3787 vinfos[2].jointtype = 1;
3788 vinfos[2].foffset = j2;
3789 vinfos[2].indices[0] = _ij2[0];
3790 vinfos[2].indices[1] = _ij2[1];
3791 vinfos[2].maxsolutions = _nj2;
3792 vinfos[3].jointtype = 1;
3793 vinfos[3].foffset = j3;
3794 vinfos[3].indices[0] = _ij3[0];
3795 vinfos[3].indices[1] = _ij3[1];
3796 vinfos[3].maxsolutions = _nj3;
3797 vinfos[4].jointtype = 1;
3798 vinfos[4].foffset = j4;
3799 vinfos[4].indices[0] = _ij4[0];
3800 vinfos[4].indices[1] = _ij4[1];
3801 vinfos[4].maxsolutions = _nj4;
3802 vinfos[5].jointtype = 1;
3803 vinfos[5].foffset = j5;
3804 vinfos[5].indices[0] = _ij5[0];
3805 vinfos[5].indices[1] = _ij5[1];
3806 vinfos[5].maxsolutions = _nj5;
3807 std::vector<int> vfree(0);
3808 solutions.AddSolution(vinfos,vfree);
3809 }
3810 }
3811 }
3812 
3813 }
3814 
3815 }
3816 
3817 } else
3818 {
3819 {
3820 IkReal j5array[1], cj5array[1], sj5array[1];
3821 bool j5valid[1]={false};
3822 _nj5 = 1;
3823 CheckValue<IkReal> x275 = IKatan2WithCheck(IkReal(((-1.0)*new_r21)),IkReal(new_r20),IKFAST_ATAN2_MAGTHRESH);
3824 if(!x275.valid){
3825 continue;
3826 }
3828 if(!x276.valid){
3829 continue;
3830 }
3831 j5array[0]=((-1.5707963267949)+(x275.value)+(((1.5707963267949)*(x276.value))));
3832 sj5array[0]=IKsin(j5array[0]);
3833 cj5array[0]=IKcos(j5array[0]);
3834 if( j5array[0] > IKPI )
3835 {
3836  j5array[0]-=IK2PI;
3837 }
3838 else if( j5array[0] < -IKPI )
3839 { j5array[0]+=IK2PI;
3840 }
3841 j5valid[0] = true;
3842 for(int ij5 = 0; ij5 < 1; ++ij5)
3843 {
3844 if( !j5valid[ij5] )
3845 {
3846  continue;
3847 }
3848 _ij5[0] = ij5; _ij5[1] = -1;
3849 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3850 {
3851 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3852 {
3853  j5valid[iij5]=false; _ij5[1] = iij5; break;
3854 }
3855 }
3856 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3857 {
3858 IkReal evalcond[12];
3859 IkReal x277=IKsin(j5);
3860 IkReal x278=IKcos(j5);
3861 IkReal x279=(cj3*new_r00);
3862 IkReal x280=(cj3*cj4);
3863 IkReal x281=((1.0)*cj3);
3864 IkReal x282=(new_r11*sj3);
3865 IkReal x283=((1.0)*cj4);
3866 IkReal x284=(new_r10*sj3);
3867 IkReal x285=((1.0)*sj4);
3868 IkReal x286=(sj3*x277);
3869 IkReal x287=((1.0)*x278);
3870 IkReal x288=(sj3*x278);
3871 evalcond[0]=(new_r21+((sj4*x277)));
3872 evalcond[1]=(new_r20+(((-1.0)*x278*x285)));
3873 evalcond[2]=(((new_r00*sj3))+x277+(((-1.0)*new_r10*x281)));
3874 evalcond[3]=(((new_r01*sj3))+x278+(((-1.0)*new_r11*x281)));
3875 evalcond[4]=(((cj4*x277))+x282+((cj3*new_r01)));
3876 evalcond[5]=(x288+new_r01+((x277*x280)));
3877 evalcond[6]=(x279+x284+(((-1.0)*x278*x283)));
3878 evalcond[7]=((((-1.0)*x280*x287))+x286+new_r00);
3879 evalcond[8]=(new_r11+((cj4*x286))+(((-1.0)*x278*x281)));
3880 evalcond[9]=((((-1.0)*x277*x281))+new_r10+(((-1.0)*x283*x288)));
3881 evalcond[10]=(x278+(((-1.0)*new_r20*x285))+(((-1.0)*x279*x283))+(((-1.0)*x283*x284)));
3882 evalcond[11]=((((-1.0)*x277))+(((-1.0)*x282*x283))+(((-1.0)*new_r01*x280))+(((-1.0)*new_r21*x285)));
3883 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
3884 {
3885 continue;
3886 }
3887 }
3888 
3889 {
3890 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3891 vinfos[0].jointtype = 1;
3892 vinfos[0].foffset = j0;
3893 vinfos[0].indices[0] = _ij0[0];
3894 vinfos[0].indices[1] = _ij0[1];
3895 vinfos[0].maxsolutions = _nj0;
3896 vinfos[1].jointtype = 1;
3897 vinfos[1].foffset = j1;
3898 vinfos[1].indices[0] = _ij1[0];
3899 vinfos[1].indices[1] = _ij1[1];
3900 vinfos[1].maxsolutions = _nj1;
3901 vinfos[2].jointtype = 1;
3902 vinfos[2].foffset = j2;
3903 vinfos[2].indices[0] = _ij2[0];
3904 vinfos[2].indices[1] = _ij2[1];
3905 vinfos[2].maxsolutions = _nj2;
3906 vinfos[3].jointtype = 1;
3907 vinfos[3].foffset = j3;
3908 vinfos[3].indices[0] = _ij3[0];
3909 vinfos[3].indices[1] = _ij3[1];
3910 vinfos[3].maxsolutions = _nj3;
3911 vinfos[4].jointtype = 1;
3912 vinfos[4].foffset = j4;
3913 vinfos[4].indices[0] = _ij4[0];
3914 vinfos[4].indices[1] = _ij4[1];
3915 vinfos[4].maxsolutions = _nj4;
3916 vinfos[5].jointtype = 1;
3917 vinfos[5].foffset = j5;
3918 vinfos[5].indices[0] = _ij5[0];
3919 vinfos[5].indices[1] = _ij5[1];
3920 vinfos[5].maxsolutions = _nj5;
3921 std::vector<int> vfree(0);
3922 solutions.AddSolution(vinfos,vfree);
3923 }
3924 }
3925 }
3926 
3927 }
3928 
3929 }
3930 }
3931 }
3932 
3933 }
3934 
3935 }
3936 
3937 } else
3938 {
3939 {
3940 IkReal j3array[1], cj3array[1], sj3array[1];
3941 bool j3valid[1]={false};
3942 _nj3 = 1;
3944 if(!x289.valid){
3945 continue;
3946 }
3947 CheckValue<IkReal> x290 = IKatan2WithCheck(IkReal(((-1.0)*new_r12)),IkReal(((-1.0)*new_r02)),IKFAST_ATAN2_MAGTHRESH);
3948 if(!x290.valid){
3949 continue;
3950 }
3951 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x289.value)))+(x290.value));
3952 sj3array[0]=IKsin(j3array[0]);
3953 cj3array[0]=IKcos(j3array[0]);
3954 if( j3array[0] > IKPI )
3955 {
3956  j3array[0]-=IK2PI;
3957 }
3958 else if( j3array[0] < -IKPI )
3959 { j3array[0]+=IK2PI;
3960 }
3961 j3valid[0] = true;
3962 for(int ij3 = 0; ij3 < 1; ++ij3)
3963 {
3964 if( !j3valid[ij3] )
3965 {
3966  continue;
3967 }
3968 _ij3[0] = ij3; _ij3[1] = -1;
3969 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
3970 {
3971 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
3972 {
3973  j3valid[iij3]=false; _ij3[1] = iij3; break;
3974 }
3975 }
3976 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
3977 {
3978 IkReal evalcond[8];
3979 IkReal x291=IKcos(j3);
3980 IkReal x292=IKsin(j3);
3981 IkReal x293=((1.0)*cj4);
3982 IkReal x294=(sj4*x292);
3983 IkReal x295=(new_r12*x292);
3984 IkReal x296=(sj4*x291);
3985 IkReal x297=(new_r02*x291);
3986 evalcond[0]=(x296+new_r02);
3987 evalcond[1]=(x294+new_r12);
3988 evalcond[2]=(((new_r12*x291))+(((-1.0)*new_r02*x292)));
3989 evalcond[3]=(sj4+x295+x297);
3990 evalcond[4]=((((-1.0)*new_r20*x293))+((new_r10*x294))+((new_r00*x296)));
3991 evalcond[5]=((((-1.0)*new_r21*x293))+((new_r11*x294))+((new_r01*x296)));
3992 evalcond[6]=((1.0)+((new_r02*x296))+((new_r12*x294))+(((-1.0)*new_r22*x293)));
3993 evalcond[7]=((((-1.0)*x293*x297))+(((-1.0)*x293*x295))+(((-1.0)*new_r22*sj4)));
3994 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
3995 {
3996 continue;
3997 }
3998 }
3999 
4000 {
4001 IkReal j5eval[3];
4002 j5eval[0]=sj4;
4003 j5eval[1]=IKsign(sj4);
4004 j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21)));
4005 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
4006 {
4007 {
4008 IkReal j5eval[2];
4009 j5eval[0]=sj4;
4010 j5eval[1]=sj3;
4011 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
4012 {
4013 {
4014 IkReal j5eval[2];
4015 j5eval[0]=sj4;
4016 j5eval[1]=cj3;
4017 if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
4018 {
4019 {
4020 IkReal evalcond[5];
4021 bool bgotonextstatement = true;
4022 do
4023 {
4024 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959)));
4025 evalcond[1]=new_r02;
4026 evalcond[2]=new_r12;
4027 evalcond[3]=new_r21;
4028 evalcond[4]=new_r20;
4029 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
4030 {
4031 bgotonextstatement=false;
4032 {
4033 IkReal j5array[1], cj5array[1], sj5array[1];
4034 bool j5valid[1]={false};
4035 _nj5 = 1;
4036 IkReal x298=((1.0)*new_r01);
4037 if( IKabs(((((-1.0)*cj3*x298))+(((-1.0)*new_r00*sj3)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*sj3*x298))+((cj3*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*cj3*x298))+(((-1.0)*new_r00*sj3))))+IKsqr(((((-1.0)*sj3*x298))+((cj3*new_r00))))-1) <= IKFAST_SINCOS_THRESH )
4038  continue;
4039 j5array[0]=IKatan2(((((-1.0)*cj3*x298))+(((-1.0)*new_r00*sj3))), ((((-1.0)*sj3*x298))+((cj3*new_r00))));
4040 sj5array[0]=IKsin(j5array[0]);
4041 cj5array[0]=IKcos(j5array[0]);
4042 if( j5array[0] > IKPI )
4043 {
4044  j5array[0]-=IK2PI;
4045 }
4046 else if( j5array[0] < -IKPI )
4047 { j5array[0]+=IK2PI;
4048 }
4049 j5valid[0] = true;
4050 for(int ij5 = 0; ij5 < 1; ++ij5)
4051 {
4052 if( !j5valid[ij5] )
4053 {
4054  continue;
4055 }
4056 _ij5[0] = ij5; _ij5[1] = -1;
4057 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4058 {
4059 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4060 {
4061  j5valid[iij5]=false; _ij5[1] = iij5; break;
4062 }
4063 }
4064 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4065 {
4066 IkReal evalcond[8];
4067 IkReal x299=IKsin(j5);
4068 IkReal x300=IKcos(j5);
4069 IkReal x301=((1.0)*cj3);
4070 IkReal x302=(sj3*x299);
4071 IkReal x303=((1.0)*x300);
4072 IkReal x304=(x300*x301);
4073 evalcond[0]=(((new_r11*sj3))+x299+((cj3*new_r01)));
4074 evalcond[1]=(((new_r00*sj3))+x299+(((-1.0)*new_r10*x301)));
4075 evalcond[2]=(((new_r01*sj3))+x300+(((-1.0)*new_r11*x301)));
4076 evalcond[3]=(((cj3*x299))+((sj3*x300))+new_r01);
4077 evalcond[4]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x303)));
4078 evalcond[5]=(x302+new_r00+(((-1.0)*x304)));
4079 evalcond[6]=(x302+new_r11+(((-1.0)*x304)));
4080 evalcond[7]=((((-1.0)*sj3*x303))+(((-1.0)*x299*x301))+new_r10);
4081 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
4082 {
4083 continue;
4084 }
4085 }
4086 
4087 {
4088 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4089 vinfos[0].jointtype = 1;
4090 vinfos[0].foffset = j0;
4091 vinfos[0].indices[0] = _ij0[0];
4092 vinfos[0].indices[1] = _ij0[1];
4093 vinfos[0].maxsolutions = _nj0;
4094 vinfos[1].jointtype = 1;
4095 vinfos[1].foffset = j1;
4096 vinfos[1].indices[0] = _ij1[0];
4097 vinfos[1].indices[1] = _ij1[1];
4098 vinfos[1].maxsolutions = _nj1;
4099 vinfos[2].jointtype = 1;
4100 vinfos[2].foffset = j2;
4101 vinfos[2].indices[0] = _ij2[0];
4102 vinfos[2].indices[1] = _ij2[1];
4103 vinfos[2].maxsolutions = _nj2;
4104 vinfos[3].jointtype = 1;
4105 vinfos[3].foffset = j3;
4106 vinfos[3].indices[0] = _ij3[0];
4107 vinfos[3].indices[1] = _ij3[1];
4108 vinfos[3].maxsolutions = _nj3;
4109 vinfos[4].jointtype = 1;
4110 vinfos[4].foffset = j4;
4111 vinfos[4].indices[0] = _ij4[0];
4112 vinfos[4].indices[1] = _ij4[1];
4113 vinfos[4].maxsolutions = _nj4;
4114 vinfos[5].jointtype = 1;
4115 vinfos[5].foffset = j5;
4116 vinfos[5].indices[0] = _ij5[0];
4117 vinfos[5].indices[1] = _ij5[1];
4118 vinfos[5].maxsolutions = _nj5;
4119 std::vector<int> vfree(0);
4120 solutions.AddSolution(vinfos,vfree);
4121 }
4122 }
4123 }
4124 
4125 }
4126 } while(0);
4127 if( bgotonextstatement )
4128 {
4129 bool bgotonextstatement = true;
4130 do
4131 {
4132 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959)));
4133 evalcond[1]=new_r02;
4134 evalcond[2]=new_r12;
4135 evalcond[3]=new_r21;
4136 evalcond[4]=new_r20;
4137 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
4138 {
4139 bgotonextstatement=false;
4140 {
4141 IkReal j5array[1], cj5array[1], sj5array[1];
4142 bool j5valid[1]={false};
4143 _nj5 = 1;
4144 IkReal x305=((1.0)*sj3);
4145 if( IKabs((((cj3*new_r01))+(((-1.0)*new_r00*x305)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*cj3*new_r00))+(((-1.0)*new_r01*x305)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((cj3*new_r01))+(((-1.0)*new_r00*x305))))+IKsqr(((((-1.0)*cj3*new_r00))+(((-1.0)*new_r01*x305))))-1) <= IKFAST_SINCOS_THRESH )
4146  continue;
4147 j5array[0]=IKatan2((((cj3*new_r01))+(((-1.0)*new_r00*x305))), ((((-1.0)*cj3*new_r00))+(((-1.0)*new_r01*x305))));
4148 sj5array[0]=IKsin(j5array[0]);
4149 cj5array[0]=IKcos(j5array[0]);
4150 if( j5array[0] > IKPI )
4151 {
4152  j5array[0]-=IK2PI;
4153 }
4154 else if( j5array[0] < -IKPI )
4155 { j5array[0]+=IK2PI;
4156 }
4157 j5valid[0] = true;
4158 for(int ij5 = 0; ij5 < 1; ++ij5)
4159 {
4160 if( !j5valid[ij5] )
4161 {
4162  continue;
4163 }
4164 _ij5[0] = ij5; _ij5[1] = -1;
4165 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4166 {
4167 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4168 {
4169  j5valid[iij5]=false; _ij5[1] = iij5; break;
4170 }
4171 }
4172 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4173 {
4174 IkReal evalcond[8];
4175 IkReal x306=IKcos(j5);
4176 IkReal x307=IKsin(j5);
4177 IkReal x308=((1.0)*cj3);
4178 IkReal x309=(sj3*x306);
4179 IkReal x310=((1.0)*x307);
4180 IkReal x311=(x307*x308);
4181 evalcond[0]=(((new_r10*sj3))+x306+((cj3*new_r00)));
4182 evalcond[1]=(((new_r00*sj3))+x307+(((-1.0)*new_r10*x308)));
4183 evalcond[2]=(((new_r01*sj3))+x306+(((-1.0)*new_r11*x308)));
4184 evalcond[3]=(((new_r11*sj3))+(((-1.0)*x310))+((cj3*new_r01)));
4185 evalcond[4]=(((sj3*x307))+((cj3*x306))+new_r00);
4186 evalcond[5]=(x309+(((-1.0)*x311))+new_r01);
4187 evalcond[6]=(x309+(((-1.0)*x311))+new_r10);
4188 evalcond[7]=((((-1.0)*sj3*x310))+(((-1.0)*x306*x308))+new_r11);
4189 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
4190 {
4191 continue;
4192 }
4193 }
4194 
4195 {
4196 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4197 vinfos[0].jointtype = 1;
4198 vinfos[0].foffset = j0;
4199 vinfos[0].indices[0] = _ij0[0];
4200 vinfos[0].indices[1] = _ij0[1];
4201 vinfos[0].maxsolutions = _nj0;
4202 vinfos[1].jointtype = 1;
4203 vinfos[1].foffset = j1;
4204 vinfos[1].indices[0] = _ij1[0];
4205 vinfos[1].indices[1] = _ij1[1];
4206 vinfos[1].maxsolutions = _nj1;
4207 vinfos[2].jointtype = 1;
4208 vinfos[2].foffset = j2;
4209 vinfos[2].indices[0] = _ij2[0];
4210 vinfos[2].indices[1] = _ij2[1];
4211 vinfos[2].maxsolutions = _nj2;
4212 vinfos[3].jointtype = 1;
4213 vinfos[3].foffset = j3;
4214 vinfos[3].indices[0] = _ij3[0];
4215 vinfos[3].indices[1] = _ij3[1];
4216 vinfos[3].maxsolutions = _nj3;
4217 vinfos[4].jointtype = 1;
4218 vinfos[4].foffset = j4;
4219 vinfos[4].indices[0] = _ij4[0];
4220 vinfos[4].indices[1] = _ij4[1];
4221 vinfos[4].maxsolutions = _nj4;
4222 vinfos[5].jointtype = 1;
4223 vinfos[5].foffset = j5;
4224 vinfos[5].indices[0] = _ij5[0];
4225 vinfos[5].indices[1] = _ij5[1];
4226 vinfos[5].maxsolutions = _nj5;
4227 std::vector<int> vfree(0);
4228 solutions.AddSolution(vinfos,vfree);
4229 }
4230 }
4231 }
4232 
4233 }
4234 } while(0);
4235 if( bgotonextstatement )
4236 {
4237 bool bgotonextstatement = true;
4238 do
4239 {
4240 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959)));
4241 evalcond[1]=new_r02;
4242 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4243 {
4244 bgotonextstatement=false;
4245 {
4246 IkReal j5array[1], cj5array[1], sj5array[1];
4247 bool j5valid[1]={false};
4248 _nj5 = 1;
4249 if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(((-1.0)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
4250  continue;
4251 j5array[0]=IKatan2(((-1.0)*new_r00), ((-1.0)*new_r01));
4252 sj5array[0]=IKsin(j5array[0]);
4253 cj5array[0]=IKcos(j5array[0]);
4254 if( j5array[0] > IKPI )
4255 {
4256  j5array[0]-=IK2PI;
4257 }
4258 else if( j5array[0] < -IKPI )
4259 { j5array[0]+=IK2PI;
4260 }
4261 j5valid[0] = true;
4262 for(int ij5 = 0; ij5 < 1; ++ij5)
4263 {
4264 if( !j5valid[ij5] )
4265 {
4266  continue;
4267 }
4268 _ij5[0] = ij5; _ij5[1] = -1;
4269 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4270 {
4271 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4272 {
4273  j5valid[iij5]=false; _ij5[1] = iij5; break;
4274 }
4275 }
4276 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4277 {
4278 IkReal evalcond[8];
4279 IkReal x312=IKsin(j5);
4280 IkReal x313=IKcos(j5);
4281 IkReal x314=((1.0)*cj4);
4282 IkReal x315=((1.0)*sj4);
4283 evalcond[0]=(x312+new_r00);
4284 evalcond[1]=(x313+new_r01);
4285 evalcond[2]=(((sj4*x312))+new_r21);
4286 evalcond[3]=(((cj4*x312))+new_r11);
4287 evalcond[4]=((((-1.0)*x313*x315))+new_r20);
4288 evalcond[5]=((((-1.0)*x313*x314))+new_r10);
4289 evalcond[6]=((((-1.0)*new_r20*x315))+x313+(((-1.0)*new_r10*x314)));
4290 evalcond[7]=((((-1.0)*new_r21*x315))+(((-1.0)*new_r11*x314))+(((-1.0)*x312)));
4291 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
4292 {
4293 continue;
4294 }
4295 }
4296 
4297 {
4298 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4299 vinfos[0].jointtype = 1;
4300 vinfos[0].foffset = j0;
4301 vinfos[0].indices[0] = _ij0[0];
4302 vinfos[0].indices[1] = _ij0[1];
4303 vinfos[0].maxsolutions = _nj0;
4304 vinfos[1].jointtype = 1;
4305 vinfos[1].foffset = j1;
4306 vinfos[1].indices[0] = _ij1[0];
4307 vinfos[1].indices[1] = _ij1[1];
4308 vinfos[1].maxsolutions = _nj1;
4309 vinfos[2].jointtype = 1;
4310 vinfos[2].foffset = j2;
4311 vinfos[2].indices[0] = _ij2[0];
4312 vinfos[2].indices[1] = _ij2[1];
4313 vinfos[2].maxsolutions = _nj2;
4314 vinfos[3].jointtype = 1;
4315 vinfos[3].foffset = j3;
4316 vinfos[3].indices[0] = _ij3[0];
4317 vinfos[3].indices[1] = _ij3[1];
4318 vinfos[3].maxsolutions = _nj3;
4319 vinfos[4].jointtype = 1;
4320 vinfos[4].foffset = j4;
4321 vinfos[4].indices[0] = _ij4[0];
4322 vinfos[4].indices[1] = _ij4[1];
4323 vinfos[4].maxsolutions = _nj4;
4324 vinfos[5].jointtype = 1;
4325 vinfos[5].foffset = j5;
4326 vinfos[5].indices[0] = _ij5[0];
4327 vinfos[5].indices[1] = _ij5[1];
4328 vinfos[5].maxsolutions = _nj5;
4329 std::vector<int> vfree(0);
4330 solutions.AddSolution(vinfos,vfree);
4331 }
4332 }
4333 }
4334 
4335 }
4336 } while(0);
4337 if( bgotonextstatement )
4338 {
4339 bool bgotonextstatement = true;
4340 do
4341 {
4342 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959)));
4343 evalcond[1]=new_r02;
4344 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4345 {
4346 bgotonextstatement=false;
4347 {
4348 IkReal j5array[1], cj5array[1], sj5array[1];
4349 bool j5valid[1]={false};
4350 _nj5 = 1;
4351 if( IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r00)+IKsqr(new_r01)-1) <= IKFAST_SINCOS_THRESH )
4352  continue;
4353 j5array[0]=IKatan2(new_r00, new_r01);
4354 sj5array[0]=IKsin(j5array[0]);
4355 cj5array[0]=IKcos(j5array[0]);
4356 if( j5array[0] > IKPI )
4357 {
4358  j5array[0]-=IK2PI;
4359 }
4360 else if( j5array[0] < -IKPI )
4361 { j5array[0]+=IK2PI;
4362 }
4363 j5valid[0] = true;
4364 for(int ij5 = 0; ij5 < 1; ++ij5)
4365 {
4366 if( !j5valid[ij5] )
4367 {
4368  continue;
4369 }
4370 _ij5[0] = ij5; _ij5[1] = -1;
4371 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4372 {
4373 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4374 {
4375  j5valid[iij5]=false; _ij5[1] = iij5; break;
4376 }
4377 }
4378 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4379 {
4380 IkReal evalcond[8];
4381 IkReal x316=IKsin(j5);
4382 IkReal x317=IKcos(j5);
4383 IkReal x318=((1.0)*sj4);
4384 IkReal x319=((1.0)*x317);
4385 evalcond[0]=(((sj4*x316))+new_r21);
4386 evalcond[1]=(x316+(((-1.0)*new_r00)));
4387 evalcond[2]=(x317+(((-1.0)*new_r01)));
4388 evalcond[3]=(new_r20+(((-1.0)*x317*x318)));
4389 evalcond[4]=(((cj4*x316))+(((-1.0)*new_r11)));
4390 evalcond[5]=((((-1.0)*cj4*x319))+(((-1.0)*new_r10)));
4391 evalcond[6]=((((-1.0)*new_r20*x318))+((cj4*new_r10))+x317);
4392 evalcond[7]=((((-1.0)*new_r21*x318))+((cj4*new_r11))+(((-1.0)*x316)));
4393 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
4394 {
4395 continue;
4396 }
4397 }
4398 
4399 {
4400 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4401 vinfos[0].jointtype = 1;
4402 vinfos[0].foffset = j0;
4403 vinfos[0].indices[0] = _ij0[0];
4404 vinfos[0].indices[1] = _ij0[1];
4405 vinfos[0].maxsolutions = _nj0;
4406 vinfos[1].jointtype = 1;
4407 vinfos[1].foffset = j1;
4408 vinfos[1].indices[0] = _ij1[0];
4409 vinfos[1].indices[1] = _ij1[1];
4410 vinfos[1].maxsolutions = _nj1;
4411 vinfos[2].jointtype = 1;
4412 vinfos[2].foffset = j2;
4413 vinfos[2].indices[0] = _ij2[0];
4414 vinfos[2].indices[1] = _ij2[1];
4415 vinfos[2].maxsolutions = _nj2;
4416 vinfos[3].jointtype = 1;
4417 vinfos[3].foffset = j3;
4418 vinfos[3].indices[0] = _ij3[0];
4419 vinfos[3].indices[1] = _ij3[1];
4420 vinfos[3].maxsolutions = _nj3;
4421 vinfos[4].jointtype = 1;
4422 vinfos[4].foffset = j4;
4423 vinfos[4].indices[0] = _ij4[0];
4424 vinfos[4].indices[1] = _ij4[1];
4425 vinfos[4].maxsolutions = _nj4;
4426 vinfos[5].jointtype = 1;
4427 vinfos[5].foffset = j5;
4428 vinfos[5].indices[0] = _ij5[0];
4429 vinfos[5].indices[1] = _ij5[1];
4430 vinfos[5].maxsolutions = _nj5;
4431 std::vector<int> vfree(0);
4432 solutions.AddSolution(vinfos,vfree);
4433 }
4434 }
4435 }
4436 
4437 }
4438 } while(0);
4439 if( bgotonextstatement )
4440 {
4441 bool bgotonextstatement = true;
4442 do
4443 {
4444 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j3))), 6.28318530717959)));
4445 evalcond[1]=new_r12;
4446 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4447 {
4448 bgotonextstatement=false;
4449 {
4450 IkReal j5array[1], cj5array[1], sj5array[1];
4451 bool j5valid[1]={false};
4452 _nj5 = 1;
4453 if( IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r10)+IKsqr(new_r11)-1) <= IKFAST_SINCOS_THRESH )
4454  continue;
4455 j5array[0]=IKatan2(new_r10, new_r11);
4456 sj5array[0]=IKsin(j5array[0]);
4457 cj5array[0]=IKcos(j5array[0]);
4458 if( j5array[0] > IKPI )
4459 {
4460  j5array[0]-=IK2PI;
4461 }
4462 else if( j5array[0] < -IKPI )
4463 { j5array[0]+=IK2PI;
4464 }
4465 j5valid[0] = true;
4466 for(int ij5 = 0; ij5 < 1; ++ij5)
4467 {
4468 if( !j5valid[ij5] )
4469 {
4470  continue;
4471 }
4472 _ij5[0] = ij5; _ij5[1] = -1;
4473 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4474 {
4475 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4476 {
4477  j5valid[iij5]=false; _ij5[1] = iij5; break;
4478 }
4479 }
4480 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4481 {
4482 IkReal evalcond[8];
4483 IkReal x320=IKcos(j5);
4484 IkReal x321=IKsin(j5);
4485 IkReal x322=((1.0)*cj4);
4486 IkReal x323=((1.0)*sj4);
4487 IkReal x324=((1.0)*x321);
4488 evalcond[0]=(new_r20+((new_r02*x320)));
4489 evalcond[1]=(x321+(((-1.0)*new_r10)));
4490 evalcond[2]=(x320+(((-1.0)*new_r11)));
4491 evalcond[3]=(((cj4*x321))+new_r01);
4492 evalcond[4]=((((-1.0)*new_r02*x324))+new_r21);
4493 evalcond[5]=((((-1.0)*x320*x322))+new_r00);
4494 evalcond[6]=(x320+(((-1.0)*new_r00*x322))+(((-1.0)*new_r20*x323)));
4495 evalcond[7]=((((-1.0)*x324))+(((-1.0)*new_r01*x322))+(((-1.0)*new_r21*x323)));
4496 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
4497 {
4498 continue;
4499 }
4500 }
4501 
4502 {
4503 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4504 vinfos[0].jointtype = 1;
4505 vinfos[0].foffset = j0;
4506 vinfos[0].indices[0] = _ij0[0];
4507 vinfos[0].indices[1] = _ij0[1];
4508 vinfos[0].maxsolutions = _nj0;
4509 vinfos[1].jointtype = 1;
4510 vinfos[1].foffset = j1;
4511 vinfos[1].indices[0] = _ij1[0];
4512 vinfos[1].indices[1] = _ij1[1];
4513 vinfos[1].maxsolutions = _nj1;
4514 vinfos[2].jointtype = 1;
4515 vinfos[2].foffset = j2;
4516 vinfos[2].indices[0] = _ij2[0];
4517 vinfos[2].indices[1] = _ij2[1];
4518 vinfos[2].maxsolutions = _nj2;
4519 vinfos[3].jointtype = 1;
4520 vinfos[3].foffset = j3;
4521 vinfos[3].indices[0] = _ij3[0];
4522 vinfos[3].indices[1] = _ij3[1];
4523 vinfos[3].maxsolutions = _nj3;
4524 vinfos[4].jointtype = 1;
4525 vinfos[4].foffset = j4;
4526 vinfos[4].indices[0] = _ij4[0];
4527 vinfos[4].indices[1] = _ij4[1];
4528 vinfos[4].maxsolutions = _nj4;
4529 vinfos[5].jointtype = 1;
4530 vinfos[5].foffset = j5;
4531 vinfos[5].indices[0] = _ij5[0];
4532 vinfos[5].indices[1] = _ij5[1];
4533 vinfos[5].maxsolutions = _nj5;
4534 std::vector<int> vfree(0);
4535 solutions.AddSolution(vinfos,vfree);
4536 }
4537 }
4538 }
4539 
4540 }
4541 } while(0);
4542 if( bgotonextstatement )
4543 {
4544 bool bgotonextstatement = true;
4545 do
4546 {
4547 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j3)))), 6.28318530717959)));
4548 evalcond[1]=new_r12;
4549 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4550 {
4551 bgotonextstatement=false;
4552 {
4553 IkReal j5array[1], cj5array[1], sj5array[1];
4554 bool j5valid[1]={false};
4555 _nj5 = 1;
4556 if( IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r10))+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH )
4557  continue;
4558 j5array[0]=IKatan2(((-1.0)*new_r10), ((-1.0)*new_r11));
4559 sj5array[0]=IKsin(j5array[0]);
4560 cj5array[0]=IKcos(j5array[0]);
4561 if( j5array[0] > IKPI )
4562 {
4563  j5array[0]-=IK2PI;
4564 }
4565 else if( j5array[0] < -IKPI )
4566 { j5array[0]+=IK2PI;
4567 }
4568 j5valid[0] = true;
4569 for(int ij5 = 0; ij5 < 1; ++ij5)
4570 {
4571 if( !j5valid[ij5] )
4572 {
4573  continue;
4574 }
4575 _ij5[0] = ij5; _ij5[1] = -1;
4576 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4577 {
4578 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4579 {
4580  j5valid[iij5]=false; _ij5[1] = iij5; break;
4581 }
4582 }
4583 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4584 {
4585 IkReal evalcond[8];
4586 IkReal x325=IKsin(j5);
4587 IkReal x326=IKcos(j5);
4588 IkReal x327=((1.0)*sj4);
4589 IkReal x328=((1.0)*x326);
4590 evalcond[0]=(x325+new_r10);
4591 evalcond[1]=(x326+new_r11);
4592 evalcond[2]=(new_r21+((new_r02*x325)));
4593 evalcond[3]=((((-1.0)*new_r02*x328))+new_r20);
4594 evalcond[4]=(((cj4*x325))+(((-1.0)*new_r01)));
4595 evalcond[5]=((((-1.0)*new_r00))+(((-1.0)*cj4*x328)));
4596 evalcond[6]=(((cj4*new_r00))+x326+(((-1.0)*new_r20*x327)));
4597 evalcond[7]=(((cj4*new_r01))+(((-1.0)*x325))+(((-1.0)*new_r21*x327)));
4598 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
4599 {
4600 continue;
4601 }
4602 }
4603 
4604 {
4605 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4606 vinfos[0].jointtype = 1;
4607 vinfos[0].foffset = j0;
4608 vinfos[0].indices[0] = _ij0[0];
4609 vinfos[0].indices[1] = _ij0[1];
4610 vinfos[0].maxsolutions = _nj0;
4611 vinfos[1].jointtype = 1;
4612 vinfos[1].foffset = j1;
4613 vinfos[1].indices[0] = _ij1[0];
4614 vinfos[1].indices[1] = _ij1[1];
4615 vinfos[1].maxsolutions = _nj1;
4616 vinfos[2].jointtype = 1;
4617 vinfos[2].foffset = j2;
4618 vinfos[2].indices[0] = _ij2[0];
4619 vinfos[2].indices[1] = _ij2[1];
4620 vinfos[2].maxsolutions = _nj2;
4621 vinfos[3].jointtype = 1;
4622 vinfos[3].foffset = j3;
4623 vinfos[3].indices[0] = _ij3[0];
4624 vinfos[3].indices[1] = _ij3[1];
4625 vinfos[3].maxsolutions = _nj3;
4626 vinfos[4].jointtype = 1;
4627 vinfos[4].foffset = j4;
4628 vinfos[4].indices[0] = _ij4[0];
4629 vinfos[4].indices[1] = _ij4[1];
4630 vinfos[4].maxsolutions = _nj4;
4631 vinfos[5].jointtype = 1;
4632 vinfos[5].foffset = j5;
4633 vinfos[5].indices[0] = _ij5[0];
4634 vinfos[5].indices[1] = _ij5[1];
4635 vinfos[5].maxsolutions = _nj5;
4636 std::vector<int> vfree(0);
4637 solutions.AddSolution(vinfos,vfree);
4638 }
4639 }
4640 }
4641 
4642 }
4643 } while(0);
4644 if( bgotonextstatement )
4645 {
4646 bool bgotonextstatement = true;
4647 do
4648 {
4649 evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21)));
4650 if( IKabs(evalcond[0]) < 0.0000050000000000 )
4651 {
4652 bgotonextstatement=false;
4653 {
4654 IkReal j5eval[1];
4655 new_r21=0;
4656 new_r20=0;
4657 new_r02=0;
4658 new_r12=0;
4659 j5eval[0]=1.0;
4660 if( IKabs(j5eval[0]) < 0.0000000100000000 )
4661 {
4662 continue; // no branches [j5]
4663 
4664 } else
4665 {
4666 IkReal op[2+1], zeror[2];
4667 int numroots;
4668 op[0]=-1.0;
4669 op[1]=0;
4670 op[2]=1.0;
4671 polyroots2(op,zeror,numroots);
4672 IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
4673 int numsolutions = 0;
4674 for(int ij5 = 0; ij5 < numroots; ++ij5)
4675 {
4676 IkReal htj5 = zeror[ij5];
4677 tempj5array[0]=((2.0)*(atan(htj5)));
4678 for(int kj5 = 0; kj5 < 1; ++kj5)
4679 {
4680 j5array[numsolutions] = tempj5array[kj5];
4681 if( j5array[numsolutions] > IKPI )
4682 {
4683  j5array[numsolutions]-=IK2PI;
4684 }
4685 else if( j5array[numsolutions] < -IKPI )
4686 {
4687  j5array[numsolutions]+=IK2PI;
4688 }
4689 sj5array[numsolutions] = IKsin(j5array[numsolutions]);
4690 cj5array[numsolutions] = IKcos(j5array[numsolutions]);
4691 numsolutions++;
4692 }
4693 }
4694 bool j5valid[2]={true,true};
4695 _nj5 = 2;
4696 for(int ij5 = 0; ij5 < numsolutions; ++ij5)
4697  {
4698 if( !j5valid[ij5] )
4699 {
4700  continue;
4701 }
4702  j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4703 htj5 = IKtan(j5/2);
4704 
4705 _ij5[0] = ij5; _ij5[1] = -1;
4706 for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
4707 {
4708 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4709 {
4710  j5valid[iij5]=false; _ij5[1] = iij5; break;
4711 }
4712 }
4713 {
4714 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4715 vinfos[0].jointtype = 1;
4716 vinfos[0].foffset = j0;
4717 vinfos[0].indices[0] = _ij0[0];
4718 vinfos[0].indices[1] = _ij0[1];
4719 vinfos[0].maxsolutions = _nj0;
4720 vinfos[1].jointtype = 1;
4721 vinfos[1].foffset = j1;
4722 vinfos[1].indices[0] = _ij1[0];
4723 vinfos[1].indices[1] = _ij1[1];
4724 vinfos[1].maxsolutions = _nj1;
4725 vinfos[2].jointtype = 1;
4726 vinfos[2].foffset = j2;
4727 vinfos[2].indices[0] = _ij2[0];
4728 vinfos[2].indices[1] = _ij2[1];
4729 vinfos[2].maxsolutions = _nj2;
4730 vinfos[3].jointtype = 1;
4731 vinfos[3].foffset = j3;
4732 vinfos[3].indices[0] = _ij3[0];
4733 vinfos[3].indices[1] = _ij3[1];
4734 vinfos[3].maxsolutions = _nj3;
4735 vinfos[4].jointtype = 1;
4736 vinfos[4].foffset = j4;
4737 vinfos[4].indices[0] = _ij4[0];
4738 vinfos[4].indices[1] = _ij4[1];
4739 vinfos[4].maxsolutions = _nj4;
4740 vinfos[5].jointtype = 1;
4741 vinfos[5].foffset = j5;
4742 vinfos[5].indices[0] = _ij5[0];
4743 vinfos[5].indices[1] = _ij5[1];
4744 vinfos[5].maxsolutions = _nj5;
4745 std::vector<int> vfree(0);
4746 solutions.AddSolution(vinfos,vfree);
4747 }
4748  }
4749 
4750 }
4751 
4752 }
4753 
4754 }
4755 } while(0);
4756 if( bgotonextstatement )
4757 {
4758 bool bgotonextstatement = true;
4759 do
4760 {
4761 if( 1 )
4762 {
4763 bgotonextstatement=false;
4764 continue; // branch miss [j5]
4765 
4766 }
4767 } while(0);
4768 if( bgotonextstatement )
4769 {
4770 }
4771 }
4772 }
4773 }
4774 }
4775 }
4776 }
4777 }
4778 }
4779 
4780 } else
4781 {
4782 {
4783 IkReal j5array[1], cj5array[1], sj5array[1];
4784 bool j5valid[1]={false};
4785 _nj5 = 1;
4787 if(!x330.valid){
4788 continue;
4789 }
4790 IkReal x329=x330.value;
4792 if(!x331.valid){
4793 continue;
4794 }
4795 if( IKabs(((-1.0)*new_r21*x329)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x329*(x331.value)*((((new_r11*sj4))+(((-1.0)*cj4*new_r21*sj3)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r21*x329))+IKsqr((x329*(x331.value)*((((new_r11*sj4))+(((-1.0)*cj4*new_r21*sj3))))))-1) <= IKFAST_SINCOS_THRESH )
4796  continue;
4797 j5array[0]=IKatan2(((-1.0)*new_r21*x329), (x329*(x331.value)*((((new_r11*sj4))+(((-1.0)*cj4*new_r21*sj3))))));
4798 sj5array[0]=IKsin(j5array[0]);
4799 cj5array[0]=IKcos(j5array[0]);
4800 if( j5array[0] > IKPI )
4801 {
4802  j5array[0]-=IK2PI;
4803 }
4804 else if( j5array[0] < -IKPI )
4805 { j5array[0]+=IK2PI;
4806 }
4807 j5valid[0] = true;
4808 for(int ij5 = 0; ij5 < 1; ++ij5)
4809 {
4810 if( !j5valid[ij5] )
4811 {
4812  continue;
4813 }
4814 _ij5[0] = ij5; _ij5[1] = -1;
4815 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4816 {
4817 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4818 {
4819  j5valid[iij5]=false; _ij5[1] = iij5; break;
4820 }
4821 }
4822 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4823 {
4824 IkReal evalcond[12];
4825 IkReal x332=IKsin(j5);
4826 IkReal x333=IKcos(j5);
4827 IkReal x334=(cj3*new_r00);
4828 IkReal x335=(cj3*cj4);
4829 IkReal x336=((1.0)*cj3);
4830 IkReal x337=(new_r11*sj3);
4831 IkReal x338=((1.0)*cj4);
4832 IkReal x339=(new_r10*sj3);
4833 IkReal x340=((1.0)*sj4);
4834 IkReal x341=(sj3*x332);
4835 IkReal x342=((1.0)*x333);
4836 IkReal x343=(sj3*x333);
4837 evalcond[0]=(((sj4*x332))+new_r21);
4838 evalcond[1]=(new_r20+(((-1.0)*x333*x340)));
4839 evalcond[2]=((((-1.0)*new_r10*x336))+((new_r00*sj3))+x332);
4840 evalcond[3]=((((-1.0)*new_r11*x336))+((new_r01*sj3))+x333);
4841 evalcond[4]=(x337+((cj4*x332))+((cj3*new_r01)));
4842 evalcond[5]=(((x332*x335))+x343+new_r01);
4843 evalcond[6]=((((-1.0)*x333*x338))+x339+x334);
4844 evalcond[7]=((((-1.0)*x335*x342))+x341+new_r00);
4845 evalcond[8]=((((-1.0)*x333*x336))+((cj4*x341))+new_r11);
4846 evalcond[9]=((((-1.0)*x332*x336))+new_r10+(((-1.0)*x338*x343)));
4847 evalcond[10]=((((-1.0)*x338*x339))+x333+(((-1.0)*new_r20*x340))+(((-1.0)*x334*x338)));
4848 evalcond[11]=((((-1.0)*x337*x338))+(((-1.0)*new_r01*x335))+(((-1.0)*x332))+(((-1.0)*new_r21*x340)));
4849 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
4850 {
4851 continue;
4852 }
4853 }
4854 
4855 {
4856 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4857 vinfos[0].jointtype = 1;
4858 vinfos[0].foffset = j0;
4859 vinfos[0].indices[0] = _ij0[0];
4860 vinfos[0].indices[1] = _ij0[1];
4861 vinfos[0].maxsolutions = _nj0;
4862 vinfos[1].jointtype = 1;
4863 vinfos[1].foffset = j1;
4864 vinfos[1].indices[0] = _ij1[0];
4865 vinfos[1].indices[1] = _ij1[1];
4866 vinfos[1].maxsolutions = _nj1;
4867 vinfos[2].jointtype = 1;
4868 vinfos[2].foffset = j2;
4869 vinfos[2].indices[0] = _ij2[0];
4870 vinfos[2].indices[1] = _ij2[1];
4871 vinfos[2].maxsolutions = _nj2;
4872 vinfos[3].jointtype = 1;
4873 vinfos[3].foffset = j3;
4874 vinfos[3].indices[0] = _ij3[0];
4875 vinfos[3].indices[1] = _ij3[1];
4876 vinfos[3].maxsolutions = _nj3;
4877 vinfos[4].jointtype = 1;
4878 vinfos[4].foffset = j4;
4879 vinfos[4].indices[0] = _ij4[0];
4880 vinfos[4].indices[1] = _ij4[1];
4881 vinfos[4].maxsolutions = _nj4;
4882 vinfos[5].jointtype = 1;
4883 vinfos[5].foffset = j5;
4884 vinfos[5].indices[0] = _ij5[0];
4885 vinfos[5].indices[1] = _ij5[1];
4886 vinfos[5].maxsolutions = _nj5;
4887 std::vector<int> vfree(0);
4888 solutions.AddSolution(vinfos,vfree);
4889 }
4890 }
4891 }
4892 
4893 }
4894 
4895 }
4896 
4897 } else
4898 {
4899 {
4900 IkReal j5array[1], cj5array[1], sj5array[1];
4901 bool j5valid[1]={false};
4902 _nj5 = 1;
4904 if(!x345.valid){
4905 continue;
4906 }
4907 IkReal x344=x345.value;
4909 if(!x346.valid){
4910 continue;
4911 }
4912 if( IKabs(((-1.0)*new_r21*x344)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x344*(x346.value)*(((((-1.0)*new_r01*sj4))+((cj3*cj4*new_r21)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r21*x344))+IKsqr((x344*(x346.value)*(((((-1.0)*new_r01*sj4))+((cj3*cj4*new_r21))))))-1) <= IKFAST_SINCOS_THRESH )
4913  continue;
4914 j5array[0]=IKatan2(((-1.0)*new_r21*x344), (x344*(x346.value)*(((((-1.0)*new_r01*sj4))+((cj3*cj4*new_r21))))));
4915 sj5array[0]=IKsin(j5array[0]);
4916 cj5array[0]=IKcos(j5array[0]);
4917 if( j5array[0] > IKPI )
4918 {
4919  j5array[0]-=IK2PI;
4920 }
4921 else if( j5array[0] < -IKPI )
4922 { j5array[0]+=IK2PI;
4923 }
4924 j5valid[0] = true;
4925 for(int ij5 = 0; ij5 < 1; ++ij5)
4926 {
4927 if( !j5valid[ij5] )
4928 {
4929  continue;
4930 }
4931 _ij5[0] = ij5; _ij5[1] = -1;
4932 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4933 {
4934 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4935 {
4936  j5valid[iij5]=false; _ij5[1] = iij5; break;
4937 }
4938 }
4939 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4940 {
4941 IkReal evalcond[12];
4942 IkReal x347=IKsin(j5);
4943 IkReal x348=IKcos(j5);
4944 IkReal x349=(cj3*new_r00);
4945 IkReal x350=(cj3*cj4);
4946 IkReal x351=((1.0)*cj3);
4947 IkReal x352=(new_r11*sj3);
4948 IkReal x353=((1.0)*cj4);
4949 IkReal x354=(new_r10*sj3);
4950 IkReal x355=((1.0)*sj4);
4951 IkReal x356=(sj3*x347);
4952 IkReal x357=((1.0)*x348);
4953 IkReal x358=(sj3*x348);
4954 evalcond[0]=(((sj4*x347))+new_r21);
4955 evalcond[1]=((((-1.0)*x348*x355))+new_r20);
4956 evalcond[2]=(((new_r00*sj3))+x347+(((-1.0)*new_r10*x351)));
4957 evalcond[3]=(((new_r01*sj3))+x348+(((-1.0)*new_r11*x351)));
4958 evalcond[4]=(x352+((cj4*x347))+((cj3*new_r01)));
4959 evalcond[5]=(x358+((x347*x350))+new_r01);
4960 evalcond[6]=((((-1.0)*x348*x353))+x354+x349);
4961 evalcond[7]=(x356+new_r00+(((-1.0)*x350*x357)));
4962 evalcond[8]=((((-1.0)*x348*x351))+((cj4*x356))+new_r11);
4963 evalcond[9]=((((-1.0)*x347*x351))+(((-1.0)*x353*x358))+new_r10);
4964 evalcond[10]=((((-1.0)*x349*x353))+x348+(((-1.0)*x353*x354))+(((-1.0)*new_r20*x355)));
4965 evalcond[11]=((((-1.0)*new_r01*x350))+(((-1.0)*new_r21*x355))+(((-1.0)*x352*x353))+(((-1.0)*x347)));
4966 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
4967 {
4968 continue;
4969 }
4970 }
4971 
4972 {
4973 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4974 vinfos[0].jointtype = 1;
4975 vinfos[0].foffset = j0;
4976 vinfos[0].indices[0] = _ij0[0];
4977 vinfos[0].indices[1] = _ij0[1];
4978 vinfos[0].maxsolutions = _nj0;
4979 vinfos[1].jointtype = 1;
4980 vinfos[1].foffset = j1;
4981 vinfos[1].indices[0] = _ij1[0];
4982 vinfos[1].indices[1] = _ij1[1];
4983 vinfos[1].maxsolutions = _nj1;
4984 vinfos[2].jointtype = 1;
4985 vinfos[2].foffset = j2;
4986 vinfos[2].indices[0] = _ij2[0];
4987 vinfos[2].indices[1] = _ij2[1];
4988 vinfos[2].maxsolutions = _nj2;
4989 vinfos[3].jointtype = 1;
4990 vinfos[3].foffset = j3;
4991 vinfos[3].indices[0] = _ij3[0];
4992 vinfos[3].indices[1] = _ij3[1];
4993 vinfos[3].maxsolutions = _nj3;
4994 vinfos[4].jointtype = 1;
4995 vinfos[4].foffset = j4;
4996 vinfos[4].indices[0] = _ij4[0];
4997 vinfos[4].indices[1] = _ij4[1];
4998 vinfos[4].maxsolutions = _nj4;
4999 vinfos[5].jointtype = 1;
5000 vinfos[5].foffset = j5;
5001 vinfos[5].indices[0] = _ij5[0];
5002 vinfos[5].indices[1] = _ij5[1];
5003 vinfos[5].maxsolutions = _nj5;
5004 std::vector<int> vfree(0);
5005 solutions.AddSolution(vinfos,vfree);
5006 }
5007 }
5008 }
5009 
5010 }
5011 
5012 }
5013 
5014 } else
5015 {
5016 {
5017 IkReal j5array[1], cj5array[1], sj5array[1];
5018 bool j5valid[1]={false};
5019 _nj5 = 1;
5020 CheckValue<IkReal> x359 = IKatan2WithCheck(IkReal(((-1.0)*new_r21)),IkReal(new_r20),IKFAST_ATAN2_MAGTHRESH);
5021 if(!x359.valid){
5022 continue;
5023 }
5025 if(!x360.valid){
5026 continue;
5027 }
5028 j5array[0]=((-1.5707963267949)+(x359.value)+(((1.5707963267949)*(x360.value))));
5029 sj5array[0]=IKsin(j5array[0]);
5030 cj5array[0]=IKcos(j5array[0]);
5031 if( j5array[0] > IKPI )
5032 {
5033  j5array[0]-=IK2PI;
5034 }
5035 else if( j5array[0] < -IKPI )
5036 { j5array[0]+=IK2PI;
5037 }
5038 j5valid[0] = true;
5039 for(int ij5 = 0; ij5 < 1; ++ij5)
5040 {
5041 if( !j5valid[ij5] )
5042 {
5043  continue;
5044 }
5045 _ij5[0] = ij5; _ij5[1] = -1;
5046 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5047 {
5048 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5049 {
5050  j5valid[iij5]=false; _ij5[1] = iij5; break;
5051 }
5052 }
5053 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5054 {
5055 IkReal evalcond[12];
5056 IkReal x361=IKsin(j5);
5057 IkReal x362=IKcos(j5);
5058 IkReal x363=(cj3*new_r00);
5059 IkReal x364=(cj3*cj4);
5060 IkReal x365=((1.0)*cj3);
5061 IkReal x366=(new_r11*sj3);
5062 IkReal x367=((1.0)*cj4);
5063 IkReal x368=(new_r10*sj3);
5064 IkReal x369=((1.0)*sj4);
5065 IkReal x370=(sj3*x361);
5066 IkReal x371=((1.0)*x362);
5067 IkReal x372=(sj3*x362);
5068 evalcond[0]=(((sj4*x361))+new_r21);
5069 evalcond[1]=((((-1.0)*x362*x369))+new_r20);
5070 evalcond[2]=(((new_r00*sj3))+x361+(((-1.0)*new_r10*x365)));
5071 evalcond[3]=(((new_r01*sj3))+x362+(((-1.0)*new_r11*x365)));
5072 evalcond[4]=(((cj4*x361))+x366+((cj3*new_r01)));
5073 evalcond[5]=(((x361*x364))+x372+new_r01);
5074 evalcond[6]=((((-1.0)*x362*x367))+x368+x363);
5075 evalcond[7]=(x370+new_r00+(((-1.0)*x364*x371)));
5076 evalcond[8]=((((-1.0)*x362*x365))+((cj4*x370))+new_r11);
5077 evalcond[9]=((((-1.0)*x361*x365))+(((-1.0)*x367*x372))+new_r10);
5078 evalcond[10]=((((-1.0)*x363*x367))+(((-1.0)*new_r20*x369))+(((-1.0)*x367*x368))+x362);
5079 evalcond[11]=((((-1.0)*x361))+(((-1.0)*x366*x367))+(((-1.0)*new_r01*x364))+(((-1.0)*new_r21*x369)));
5080 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
5081 {
5082 continue;
5083 }
5084 }
5085 
5086 {
5087 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5088 vinfos[0].jointtype = 1;
5089 vinfos[0].foffset = j0;
5090 vinfos[0].indices[0] = _ij0[0];
5091 vinfos[0].indices[1] = _ij0[1];
5092 vinfos[0].maxsolutions = _nj0;
5093 vinfos[1].jointtype = 1;
5094 vinfos[1].foffset = j1;
5095 vinfos[1].indices[0] = _ij1[0];
5096 vinfos[1].indices[1] = _ij1[1];
5097 vinfos[1].maxsolutions = _nj1;
5098 vinfos[2].jointtype = 1;
5099 vinfos[2].foffset = j2;
5100 vinfos[2].indices[0] = _ij2[0];
5101 vinfos[2].indices[1] = _ij2[1];
5102 vinfos[2].maxsolutions = _nj2;
5103 vinfos[3].jointtype = 1;
5104 vinfos[3].foffset = j3;
5105 vinfos[3].indices[0] = _ij3[0];
5106 vinfos[3].indices[1] = _ij3[1];
5107 vinfos[3].maxsolutions = _nj3;
5108 vinfos[4].jointtype = 1;
5109 vinfos[4].foffset = j4;
5110 vinfos[4].indices[0] = _ij4[0];
5111 vinfos[4].indices[1] = _ij4[1];
5112 vinfos[4].maxsolutions = _nj4;
5113 vinfos[5].jointtype = 1;
5114 vinfos[5].foffset = j5;
5115 vinfos[5].indices[0] = _ij5[0];
5116 vinfos[5].indices[1] = _ij5[1];
5117 vinfos[5].maxsolutions = _nj5;
5118 std::vector<int> vfree(0);
5119 solutions.AddSolution(vinfos,vfree);
5120 }
5121 }
5122 }
5123 
5124 }
5125 
5126 }
5127 }
5128 }
5129 
5130 }
5131 
5132 }
5133 
5134 } else
5135 {
5136 {
5137 IkReal j5array[1], cj5array[1], sj5array[1];
5138 bool j5valid[1]={false};
5139 _nj5 = 1;
5140 CheckValue<IkReal> x373 = IKatan2WithCheck(IkReal(((-1.0)*new_r21)),IkReal(new_r20),IKFAST_ATAN2_MAGTHRESH);
5141 if(!x373.valid){
5142 continue;
5143 }
5145 if(!x374.valid){
5146 continue;
5147 }
5148 j5array[0]=((-1.5707963267949)+(x373.value)+(((1.5707963267949)*(x374.value))));
5149 sj5array[0]=IKsin(j5array[0]);
5150 cj5array[0]=IKcos(j5array[0]);
5151 if( j5array[0] > IKPI )
5152 {
5153  j5array[0]-=IK2PI;
5154 }
5155 else if( j5array[0] < -IKPI )
5156 { j5array[0]+=IK2PI;
5157 }
5158 j5valid[0] = true;
5159 for(int ij5 = 0; ij5 < 1; ++ij5)
5160 {
5161 if( !j5valid[ij5] )
5162 {
5163  continue;
5164 }
5165 _ij5[0] = ij5; _ij5[1] = -1;
5166 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5167 {
5168 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5169 {
5170  j5valid[iij5]=false; _ij5[1] = iij5; break;
5171 }
5172 }
5173 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5174 {
5175 IkReal evalcond[2];
5176 evalcond[0]=(((sj4*(IKsin(j5))))+new_r21);
5177 evalcond[1]=((((-1.0)*sj4*(IKcos(j5))))+new_r20);
5178 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
5179 {
5180 continue;
5181 }
5182 }
5183 
5184 {
5185 IkReal j3eval[3];
5186 j3eval[0]=sj4;
5187 j3eval[1]=IKsign(sj4);
5188 j3eval[2]=((IKabs(new_r12))+(IKabs(new_r02)));
5189 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5190 {
5191 {
5192 IkReal j3eval[2];
5193 j3eval[0]=new_r12;
5194 j3eval[1]=sj4;
5195 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
5196 {
5197 {
5198 IkReal evalcond[5];
5199 bool bgotonextstatement = true;
5200 do
5201 {
5202 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959)));
5203 evalcond[1]=new_r02;
5204 evalcond[2]=new_r12;
5205 evalcond[3]=new_r21;
5206 evalcond[4]=new_r20;
5207 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
5208 {
5209 bgotonextstatement=false;
5210 {
5211 IkReal j3eval[3];
5212 sj4=0;
5213 cj4=1.0;
5214 j4=0;
5215 IkReal x375=((1.0)*new_r11);
5216 IkReal x376=((((-1.0)*new_r10*x375))+(((-1.0)*new_r00*new_r01)));
5217 j3eval[0]=x376;
5218 j3eval[1]=((IKabs((((new_r10*sj5))+((new_r01*sj5)))))+(IKabs(((((-1.0)*sj5*x375))+((new_r00*sj5))))));
5219 j3eval[2]=IKsign(x376);
5220 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5221 {
5222 {
5223 IkReal j3eval[3];
5224 sj4=0;
5225 cj4=1.0;
5226 j4=0;
5227 IkReal x377=((((-1.0)*(new_r01*new_r01)))+(((-1.0)*(new_r11*new_r11))));
5228 j3eval[0]=x377;
5229 j3eval[1]=((IKabs((((new_r11*sj5))+((cj5*new_r01)))))+(IKabs((((new_r01*sj5))+(((-1.0)*cj5*new_r11))))));
5230 j3eval[2]=IKsign(x377);
5231 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5232 {
5233 {
5234 IkReal j3eval[3];
5235 sj4=0;
5236 cj4=1.0;
5237 j4=0;
5238 IkReal x378=((1.0)*new_r11);
5239 IkReal x379=((((-1.0)*cj5*x378))+(((-1.0)*new_r01*sj5)));
5240 j3eval[0]=x379;
5241 j3eval[1]=IKsign(x379);
5242 j3eval[2]=((IKabs((((new_r00*new_r01))+((cj5*sj5)))))+(IKabs(((1.0)+(((-1.0)*new_r00*x378))+(((-1.0)*(cj5*cj5)))))));
5243 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5244 {
5245 {
5246 IkReal evalcond[1];
5247 bool bgotonextstatement = true;
5248 do
5249 {
5250 IkReal x380=((-1.0)*new_r01);
5251 IkReal x382 = ((new_r01*new_r01)+(new_r11*new_r11));
5252 if(IKabs(x382)==0){
5253 continue;
5254 }
5255 IkReal x381=pow(x382,-0.5);
5256 CheckValue<IkReal> x383 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(x380),IKFAST_ATAN2_MAGTHRESH);
5257 if(!x383.valid){
5258 continue;
5259 }
5260 IkReal gconst0=((-1.0)*(x383.value));
5261 IkReal gconst1=(new_r11*x381);
5262 IkReal gconst2=(x380*x381);
5263 CheckValue<IkReal> x384 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
5264 if(!x384.valid){
5265 continue;
5266 }
5267 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x384.value)+j5)))), 6.28318530717959)));
5268 if( IKabs(evalcond[0]) < 0.0000050000000000 )
5269 {
5270 bgotonextstatement=false;
5271 {
5272 IkReal j3eval[3];
5273 IkReal x385=((-1.0)*new_r01);
5274 CheckValue<IkReal> x388 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(x385),IKFAST_ATAN2_MAGTHRESH);
5275 if(!x388.valid){
5276 continue;
5277 }
5278 IkReal x386=((-1.0)*(x388.value));
5279 IkReal x387=x381;
5280 sj4=0;
5281 cj4=1.0;
5282 j4=0;
5283 sj5=gconst1;
5284 cj5=gconst2;
5285 j5=x386;
5286 IkReal gconst0=x386;
5287 IkReal gconst1=(new_r11*x387);
5288 IkReal gconst2=(x385*x387);
5289 IkReal x389=new_r11*new_r11;
5290 IkReal x390=(new_r10*new_r11);
5291 IkReal x391=((((-1.0)*x390))+(((-1.0)*new_r00*new_r01)));
5292 IkReal x392=x381;
5293 IkReal x393=(new_r11*x392);
5294 j3eval[0]=x391;
5295 j3eval[1]=((IKabs(((((-1.0)*x389*x392))+((new_r00*x393)))))+(IKabs((((new_r01*x393))+((x390*x392))))));
5296 j3eval[2]=IKsign(x391);
5297 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5298 {
5299 {
5300 IkReal j3eval[1];
5301 IkReal x394=((-1.0)*new_r01);
5302 CheckValue<IkReal> x397 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(x394),IKFAST_ATAN2_MAGTHRESH);
5303 if(!x397.valid){
5304 continue;
5305 }
5306 IkReal x395=((-1.0)*(x397.value));
5307 IkReal x396=x381;
5308 sj4=0;
5309 cj4=1.0;
5310 j4=0;
5311 sj5=gconst1;
5312 cj5=gconst2;
5313 j5=x395;
5314 IkReal gconst0=x395;
5315 IkReal gconst1=(new_r11*x396);
5316 IkReal gconst2=(x394*x396);
5317 IkReal x398=new_r11*new_r11;
5318 CheckValue<IkReal> x401=IKPowWithIntegerCheck(((new_r01*new_r01)+x398),-1);
5319 if(!x401.valid){
5320 continue;
5321 }
5322 IkReal x399=x401.value;
5323 IkReal x400=(x398*x399);
5324 j3eval[0]=((IKabs((((new_r01*new_r10))+x400)))+(IKabs((((new_r00*new_r01*x400))+((new_r00*x399*(new_r01*new_r01*new_r01)))+((new_r01*new_r11*x399))))));
5325 if( IKabs(j3eval[0]) < 0.0000010000000000 )
5326 {
5327 {
5328 IkReal j3eval[1];
5329 IkReal x402=((-1.0)*new_r01);
5330 CheckValue<IkReal> x405 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(x402),IKFAST_ATAN2_MAGTHRESH);
5331 if(!x405.valid){
5332 continue;
5333 }
5334 IkReal x403=((-1.0)*(x405.value));
5335 IkReal x404=x381;
5336 sj4=0;
5337 cj4=1.0;
5338 j4=0;
5339 sj5=gconst1;
5340 cj5=gconst2;
5341 j5=x403;
5342 IkReal gconst0=x403;
5343 IkReal gconst1=(new_r11*x404);
5344 IkReal gconst2=(x402*x404);
5345 IkReal x406=new_r01*new_r01;
5346 IkReal x407=new_r11*new_r11;
5347 CheckValue<IkReal> x414=IKPowWithIntegerCheck((x407+x406),-1);
5348 if(!x414.valid){
5349 continue;
5350 }
5351 IkReal x408=x414.value;
5352 IkReal x409=(x407*x408);
5353 CheckValue<IkReal> x415=IKPowWithIntegerCheck(((((-1.0)*x406))+(((-1.0)*x407))),-1);
5354 if(!x415.valid){
5355 continue;
5356 }
5357 IkReal x410=x415.value;
5358 IkReal x411=((1.0)*x410);
5359 IkReal x412=(new_r11*x411);
5360 IkReal x413=(new_r01*x411);
5361 j3eval[0]=((IKabs((((x406*x409))+((x408*(x406*x406)))+(((-1.0)*x409)))))+(IKabs(((((-1.0)*new_r01*x412*(new_r11*new_r11)))+(((-1.0)*x412*(new_r01*new_r01*new_r01)))+(((-1.0)*new_r01*x412))))));
5362 if( IKabs(j3eval[0]) < 0.0000010000000000 )
5363 {
5364 {
5365 IkReal evalcond[3];
5366 bool bgotonextstatement = true;
5367 do
5368 {
5369 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
5370 if( IKabs(evalcond[0]) < 0.0000050000000000 )
5371 {
5372 bgotonextstatement=false;
5373 {
5374 IkReal j3array[2], cj3array[2], sj3array[2];
5375 bool j3valid[2]={false};
5376 _nj3 = 2;
5377 CheckValue<IkReal> x416=IKPowWithIntegerCheck(gconst2,-1);
5378 if(!x416.valid){
5379 continue;
5380 }
5381 sj3array[0]=(new_r10*(x416.value));
5382 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
5383 {
5384  j3valid[0] = j3valid[1] = true;
5385  j3array[0] = IKasin(sj3array[0]);
5386  cj3array[0] = IKcos(j3array[0]);
5387  sj3array[1] = sj3array[0];
5388  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
5389  cj3array[1] = -cj3array[0];
5390 }
5391 else if( isnan(sj3array[0]) )
5392 {
5393  // probably any value will work
5394  j3valid[0] = true;
5395  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
5396 }
5397 for(int ij3 = 0; ij3 < 2; ++ij3)
5398 {
5399 if( !j3valid[ij3] )
5400 {
5401  continue;
5402 }
5403 _ij3[0] = ij3; _ij3[1] = -1;
5404 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
5405 {
5406 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5407 {
5408  j3valid[iij3]=false; _ij3[1] = iij3; break;
5409 }
5410 }
5411 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5412 {
5413 IkReal evalcond[6];
5414 IkReal x417=IKcos(j3);
5415 IkReal x418=IKsin(j3);
5416 IkReal x419=((-1.0)*x417);
5417 evalcond[0]=(new_r01*x417);
5418 evalcond[1]=(new_r10*x419);
5419 evalcond[2]=(gconst2*x419);
5420 evalcond[3]=(gconst2+((new_r01*x418)));
5421 evalcond[4]=(((gconst2*x418))+new_r01);
5422 evalcond[5]=((((-1.0)*gconst2))+((new_r10*x418)));
5423 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5424 {
5425 continue;
5426 }
5427 }
5428 
5429 {
5430 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5431 vinfos[0].jointtype = 1;
5432 vinfos[0].foffset = j0;
5433 vinfos[0].indices[0] = _ij0[0];
5434 vinfos[0].indices[1] = _ij0[1];
5435 vinfos[0].maxsolutions = _nj0;
5436 vinfos[1].jointtype = 1;
5437 vinfos[1].foffset = j1;
5438 vinfos[1].indices[0] = _ij1[0];
5439 vinfos[1].indices[1] = _ij1[1];
5440 vinfos[1].maxsolutions = _nj1;
5441 vinfos[2].jointtype = 1;
5442 vinfos[2].foffset = j2;
5443 vinfos[2].indices[0] = _ij2[0];
5444 vinfos[2].indices[1] = _ij2[1];
5445 vinfos[2].maxsolutions = _nj2;
5446 vinfos[3].jointtype = 1;
5447 vinfos[3].foffset = j3;
5448 vinfos[3].indices[0] = _ij3[0];
5449 vinfos[3].indices[1] = _ij3[1];
5450 vinfos[3].maxsolutions = _nj3;
5451 vinfos[4].jointtype = 1;
5452 vinfos[4].foffset = j4;
5453 vinfos[4].indices[0] = _ij4[0];
5454 vinfos[4].indices[1] = _ij4[1];
5455 vinfos[4].maxsolutions = _nj4;
5456 vinfos[5].jointtype = 1;
5457 vinfos[5].foffset = j5;
5458 vinfos[5].indices[0] = _ij5[0];
5459 vinfos[5].indices[1] = _ij5[1];
5460 vinfos[5].maxsolutions = _nj5;
5461 std::vector<int> vfree(0);
5462 solutions.AddSolution(vinfos,vfree);
5463 }
5464 }
5465 }
5466 
5467 }
5468 } while(0);
5469 if( bgotonextstatement )
5470 {
5471 bool bgotonextstatement = true;
5472 do
5473 {
5474 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
5475 evalcond[1]=gconst1;
5476 evalcond[2]=gconst2;
5477 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
5478 {
5479 bgotonextstatement=false;
5480 {
5481 IkReal j3eval[3];
5482 IkReal x420=((-1.0)*new_r01);
5483 CheckValue<IkReal> x422 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(x420),IKFAST_ATAN2_MAGTHRESH);
5484 if(!x422.valid){
5485 continue;
5486 }
5487 IkReal x421=((-1.0)*(x422.value));
5488 sj4=0;
5489 cj4=1.0;
5490 j4=0;
5491 sj5=gconst1;
5492 cj5=gconst2;
5493 j5=x421;
5494 new_r00=0;
5495 new_r10=0;
5496 new_r21=0;
5497 new_r22=0;
5498 IkReal gconst0=x421;
5499 IkReal gconst1=new_r11;
5500 IkReal gconst2=x420;
5501 j3eval[0]=-1.0;
5502 j3eval[1]=-1.0;
5503 j3eval[2]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01)))))));
5504 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5505 {
5506 {
5507 IkReal j3eval[3];
5508 IkReal x423=((-1.0)*new_r01);
5509 CheckValue<IkReal> x425 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(x423),IKFAST_ATAN2_MAGTHRESH);
5510 if(!x425.valid){
5511 continue;
5512 }
5513 IkReal x424=((-1.0)*(x425.value));
5514 sj4=0;
5515 cj4=1.0;
5516 j4=0;
5517 sj5=gconst1;
5518 cj5=gconst2;
5519 j5=x424;
5520 new_r00=0;
5521 new_r10=0;
5522 new_r21=0;
5523 new_r22=0;
5524 IkReal gconst0=x424;
5525 IkReal gconst1=new_r11;
5526 IkReal gconst2=x423;
5527 j3eval[0]=-1.0;
5528 j3eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11))));
5529 j3eval[2]=-1.0;
5530 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5531 {
5532 {
5533 IkReal j3eval[3];
5534 IkReal x426=((-1.0)*new_r01);
5535 CheckValue<IkReal> x428 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(x426),IKFAST_ATAN2_MAGTHRESH);
5536 if(!x428.valid){
5537 continue;
5538 }
5539 IkReal x427=((-1.0)*(x428.value));
5540 sj4=0;
5541 cj4=1.0;
5542 j4=0;
5543 sj5=gconst1;
5544 cj5=gconst2;
5545 j5=x427;
5546 new_r00=0;
5547 new_r10=0;
5548 new_r21=0;
5549 new_r22=0;
5550 IkReal gconst0=x427;
5551 IkReal gconst1=new_r11;
5552 IkReal gconst2=x426;
5553 j3eval[0]=1.0;
5554 j3eval[1]=1.0;
5555 j3eval[2]=((((0.5)*(IKabs(((-1.0)+(((2.0)*(new_r01*new_r01))))))))+(IKabs((new_r01*new_r11))));
5556 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
5557 {
5558 continue; // 3 cases reached
5559 
5560 } else
5561 {
5562 {
5563 IkReal j3array[1], cj3array[1], sj3array[1];
5564 bool j3valid[1]={false};
5565 _nj3 = 1;
5566 IkReal x429=((1.0)*new_r01);
5567 CheckValue<IkReal> x430 = IKatan2WithCheck(IkReal(((new_r01*new_r01)+(((-1.0)*(gconst1*gconst1))))),IkReal(((((-1.0)*new_r11*x429))+((gconst1*gconst2)))),IKFAST_ATAN2_MAGTHRESH);
5568 if(!x430.valid){
5569 continue;
5570 }
5571 CheckValue<IkReal> x431=IKPowWithIntegerCheck(IKsign((((gconst1*new_r11))+(((-1.0)*gconst2*x429)))),-1);
5572 if(!x431.valid){
5573 continue;
5574 }
5575 j3array[0]=((-1.5707963267949)+(x430.value)+(((1.5707963267949)*(x431.value))));
5576 sj3array[0]=IKsin(j3array[0]);
5577 cj3array[0]=IKcos(j3array[0]);
5578 if( j3array[0] > IKPI )
5579 {
5580  j3array[0]-=IK2PI;
5581 }
5582 else if( j3array[0] < -IKPI )
5583 { j3array[0]+=IK2PI;
5584 }
5585 j3valid[0] = true;
5586 for(int ij3 = 0; ij3 < 1; ++ij3)
5587 {
5588 if( !j3valid[ij3] )
5589 {
5590  continue;
5591 }
5592 _ij3[0] = ij3; _ij3[1] = -1;
5593 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
5594 {
5595 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5596 {
5597  j3valid[iij3]=false; _ij3[1] = iij3; break;
5598 }
5599 }
5600 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5601 {
5602 IkReal evalcond[6];
5603 IkReal x432=IKcos(j3);
5604 IkReal x433=IKsin(j3);
5605 IkReal x434=(gconst1*x433);
5606 IkReal x435=(gconst2*x433);
5607 IkReal x436=((1.0)*x432);
5608 IkReal x437=(gconst2*x436);
5609 evalcond[0]=(((new_r01*x432))+gconst1+((new_r11*x433)));
5610 evalcond[1]=(((gconst1*x432))+x435+new_r01);
5611 evalcond[2]=((((-1.0)*x437))+x434);
5612 evalcond[3]=(((new_r01*x433))+gconst2+(((-1.0)*new_r11*x436)));
5613 evalcond[4]=((((-1.0)*x437))+x434+new_r11);
5614 evalcond[5]=((((-1.0)*x435))+(((-1.0)*gconst1*x436)));
5615 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5616 {
5617 continue;
5618 }
5619 }
5620 
5621 {
5622 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5623 vinfos[0].jointtype = 1;
5624 vinfos[0].foffset = j0;
5625 vinfos[0].indices[0] = _ij0[0];
5626 vinfos[0].indices[1] = _ij0[1];
5627 vinfos[0].maxsolutions = _nj0;
5628 vinfos[1].jointtype = 1;
5629 vinfos[1].foffset = j1;
5630 vinfos[1].indices[0] = _ij1[0];
5631 vinfos[1].indices[1] = _ij1[1];
5632 vinfos[1].maxsolutions = _nj1;
5633 vinfos[2].jointtype = 1;
5634 vinfos[2].foffset = j2;
5635 vinfos[2].indices[0] = _ij2[0];
5636 vinfos[2].indices[1] = _ij2[1];
5637 vinfos[2].maxsolutions = _nj2;
5638 vinfos[3].jointtype = 1;
5639 vinfos[3].foffset = j3;
5640 vinfos[3].indices[0] = _ij3[0];
5641 vinfos[3].indices[1] = _ij3[1];
5642 vinfos[3].maxsolutions = _nj3;
5643 vinfos[4].jointtype = 1;
5644 vinfos[4].foffset = j4;
5645 vinfos[4].indices[0] = _ij4[0];
5646 vinfos[4].indices[1] = _ij4[1];
5647 vinfos[4].maxsolutions = _nj4;
5648 vinfos[5].jointtype = 1;
5649 vinfos[5].foffset = j5;
5650 vinfos[5].indices[0] = _ij5[0];
5651 vinfos[5].indices[1] = _ij5[1];
5652 vinfos[5].maxsolutions = _nj5;
5653 std::vector<int> vfree(0);
5654 solutions.AddSolution(vinfos,vfree);
5655 }
5656 }
5657 }
5658 
5659 }
5660 
5661 }
5662 
5663 } else
5664 {
5665 {
5666 IkReal j3array[1], cj3array[1], sj3array[1];
5667 bool j3valid[1]={false};
5668 _nj3 = 1;
5669 CheckValue<IkReal> x438=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst2*gconst2)))+(((-1.0)*(gconst1*gconst1))))),-1);
5670 if(!x438.valid){
5671 continue;
5672 }
5673 CheckValue<IkReal> x439 = IKatan2WithCheck(IkReal((gconst2*new_r01)),IkReal((gconst1*new_r01)),IKFAST_ATAN2_MAGTHRESH);
5674 if(!x439.valid){
5675 continue;
5676 }
5677 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x438.value)))+(x439.value));
5678 sj3array[0]=IKsin(j3array[0]);
5679 cj3array[0]=IKcos(j3array[0]);
5680 if( j3array[0] > IKPI )
5681 {
5682  j3array[0]-=IK2PI;
5683 }
5684 else if( j3array[0] < -IKPI )
5685 { j3array[0]+=IK2PI;
5686 }
5687 j3valid[0] = true;
5688 for(int ij3 = 0; ij3 < 1; ++ij3)
5689 {
5690 if( !j3valid[ij3] )
5691 {
5692  continue;
5693 }
5694 _ij3[0] = ij3; _ij3[1] = -1;
5695 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
5696 {
5697 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5698 {
5699  j3valid[iij3]=false; _ij3[1] = iij3; break;
5700 }
5701 }
5702 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5703 {
5704 IkReal evalcond[6];
5705 IkReal x440=IKcos(j3);
5706 IkReal x441=IKsin(j3);
5707 IkReal x442=(gconst1*x441);
5708 IkReal x443=(gconst2*x441);
5709 IkReal x444=((1.0)*x440);
5710 IkReal x445=(gconst2*x444);
5711 evalcond[0]=(((new_r01*x440))+gconst1+((new_r11*x441)));
5712 evalcond[1]=(((gconst1*x440))+x443+new_r01);
5713 evalcond[2]=((((-1.0)*x445))+x442);
5714 evalcond[3]=(((new_r01*x441))+gconst2+(((-1.0)*new_r11*x444)));
5715 evalcond[4]=((((-1.0)*x445))+x442+new_r11);
5716 evalcond[5]=((((-1.0)*x443))+(((-1.0)*gconst1*x444)));
5717 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5718 {
5719 continue;
5720 }
5721 }
5722 
5723 {
5724 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5725 vinfos[0].jointtype = 1;
5726 vinfos[0].foffset = j0;
5727 vinfos[0].indices[0] = _ij0[0];
5728 vinfos[0].indices[1] = _ij0[1];
5729 vinfos[0].maxsolutions = _nj0;
5730 vinfos[1].jointtype = 1;
5731 vinfos[1].foffset = j1;
5732 vinfos[1].indices[0] = _ij1[0];
5733 vinfos[1].indices[1] = _ij1[1];
5734 vinfos[1].maxsolutions = _nj1;
5735 vinfos[2].jointtype = 1;
5736 vinfos[2].foffset = j2;
5737 vinfos[2].indices[0] = _ij2[0];
5738 vinfos[2].indices[1] = _ij2[1];
5739 vinfos[2].maxsolutions = _nj2;
5740 vinfos[3].jointtype = 1;
5741 vinfos[3].foffset = j3;
5742 vinfos[3].indices[0] = _ij3[0];
5743 vinfos[3].indices[1] = _ij3[1];
5744 vinfos[3].maxsolutions = _nj3;
5745 vinfos[4].jointtype = 1;
5746 vinfos[4].foffset = j4;
5747 vinfos[4].indices[0] = _ij4[0];
5748 vinfos[4].indices[1] = _ij4[1];
5749 vinfos[4].maxsolutions = _nj4;
5750 vinfos[5].jointtype = 1;
5751 vinfos[5].foffset = j5;
5752 vinfos[5].indices[0] = _ij5[0];
5753 vinfos[5].indices[1] = _ij5[1];
5754 vinfos[5].maxsolutions = _nj5;
5755 std::vector<int> vfree(0);
5756 solutions.AddSolution(vinfos,vfree);
5757 }
5758 }
5759 }
5760 
5761 }
5762 
5763 }
5764 
5765 } else
5766 {
5767 {
5768 IkReal j3array[1], cj3array[1], sj3array[1];
5769 bool j3valid[1]={false};
5770 _nj3 = 1;
5771 CheckValue<IkReal> x446 = IKatan2WithCheck(IkReal(gconst1*gconst1),IkReal(((-1.0)*gconst1*gconst2)),IKFAST_ATAN2_MAGTHRESH);
5772 if(!x446.valid){
5773 continue;
5774 }
5775 CheckValue<IkReal> x447=IKPowWithIntegerCheck(IKsign((((gconst2*new_r01))+(((-1.0)*gconst1*new_r11)))),-1);
5776 if(!x447.valid){
5777 continue;
5778 }
5779 j3array[0]=((-1.5707963267949)+(x446.value)+(((1.5707963267949)*(x447.value))));
5780 sj3array[0]=IKsin(j3array[0]);
5781 cj3array[0]=IKcos(j3array[0]);
5782 if( j3array[0] > IKPI )
5783 {
5784  j3array[0]-=IK2PI;
5785 }
5786 else if( j3array[0] < -IKPI )
5787 { j3array[0]+=IK2PI;
5788 }
5789 j3valid[0] = true;
5790 for(int ij3 = 0; ij3 < 1; ++ij3)
5791 {
5792 if( !j3valid[ij3] )
5793 {
5794  continue;
5795 }
5796 _ij3[0] = ij3; _ij3[1] = -1;
5797 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
5798 {
5799 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5800 {
5801  j3valid[iij3]=false; _ij3[1] = iij3; break;
5802 }
5803 }
5804 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5805 {
5806 IkReal evalcond[6];
5807 IkReal x448=IKcos(j3);
5808 IkReal x449=IKsin(j3);
5809 IkReal x450=(gconst1*x449);
5810 IkReal x451=(gconst2*x449);
5811 IkReal x452=((1.0)*x448);
5812 IkReal x453=(gconst2*x452);
5813 evalcond[0]=(((new_r01*x448))+gconst1+((new_r11*x449)));
5814 evalcond[1]=(((gconst1*x448))+x451+new_r01);
5815 evalcond[2]=((((-1.0)*x453))+x450);
5816 evalcond[3]=(((new_r01*x449))+gconst2+(((-1.0)*new_r11*x452)));
5817 evalcond[4]=((((-1.0)*x453))+x450+new_r11);
5818 evalcond[5]=((((-1.0)*x451))+(((-1.0)*gconst1*x452)));
5819 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5820 {
5821 continue;
5822 }
5823 }
5824 
5825 {
5826 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5827 vinfos[0].jointtype = 1;
5828 vinfos[0].foffset = j0;
5829 vinfos[0].indices[0] = _ij0[0];
5830 vinfos[0].indices[1] = _ij0[1];
5831 vinfos[0].maxsolutions = _nj0;
5832 vinfos[1].jointtype = 1;
5833 vinfos[1].foffset = j1;
5834 vinfos[1].indices[0] = _ij1[0];
5835 vinfos[1].indices[1] = _ij1[1];
5836 vinfos[1].maxsolutions = _nj1;
5837 vinfos[2].jointtype = 1;
5838 vinfos[2].foffset = j2;
5839 vinfos[2].indices[0] = _ij2[0];
5840 vinfos[2].indices[1] = _ij2[1];
5841 vinfos[2].maxsolutions = _nj2;
5842 vinfos[3].jointtype = 1;
5843 vinfos[3].foffset = j3;
5844 vinfos[3].indices[0] = _ij3[0];
5845 vinfos[3].indices[1] = _ij3[1];
5846 vinfos[3].maxsolutions = _nj3;
5847 vinfos[4].jointtype = 1;
5848 vinfos[4].foffset = j4;
5849 vinfos[4].indices[0] = _ij4[0];
5850 vinfos[4].indices[1] = _ij4[1];
5851 vinfos[4].maxsolutions = _nj4;
5852 vinfos[5].jointtype = 1;
5853 vinfos[5].foffset = j5;
5854 vinfos[5].indices[0] = _ij5[0];
5855 vinfos[5].indices[1] = _ij5[1];
5856 vinfos[5].maxsolutions = _nj5;
5857 std::vector<int> vfree(0);
5858 solutions.AddSolution(vinfos,vfree);
5859 }
5860 }
5861 }
5862 
5863 }
5864 
5865 }
5866 
5867 }
5868 } while(0);
5869 if( bgotonextstatement )
5870 {
5871 bool bgotonextstatement = true;
5872 do
5873 {
5874 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
5875 if( IKabs(evalcond[0]) < 0.0000050000000000 )
5876 {
5877 bgotonextstatement=false;
5878 {
5879 IkReal j3eval[1];
5880 CheckValue<IkReal> x455 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
5881 if(!x455.valid){
5882 continue;
5883 }
5884 IkReal x454=((-1.0)*(x455.value));
5885 sj4=0;
5886 cj4=1.0;
5887 j4=0;
5888 sj5=gconst1;
5889 cj5=gconst2;
5890 j5=x454;
5891 new_r01=0;
5892 new_r10=0;
5893 IkReal gconst0=x454;
5894 IkReal x456 = new_r11*new_r11;
5895 if(IKabs(x456)==0){
5896 continue;
5897 }
5898 IkReal gconst1=(new_r11*(pow(x456,-0.5)));
5899 IkReal gconst2=0;
5900 j3eval[0]=new_r00;
5901 if( IKabs(j3eval[0]) < 0.0000010000000000 )
5902 {
5903 {
5904 IkReal j3eval[1];
5905 CheckValue<IkReal> x458 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
5906 if(!x458.valid){
5907 continue;
5908 }
5909 IkReal x457=((-1.0)*(x458.value));
5910 sj4=0;
5911 cj4=1.0;
5912 j4=0;
5913 sj5=gconst1;
5914 cj5=gconst2;
5915 j5=x457;
5916 new_r01=0;
5917 new_r10=0;
5918 IkReal gconst0=x457;
5919 IkReal x459 = new_r11*new_r11;
5920 if(IKabs(x459)==0){
5921 continue;
5922 }
5923 IkReal gconst1=(new_r11*(pow(x459,-0.5)));
5924 IkReal gconst2=0;
5925 j3eval[0]=new_r11;
5926 if( IKabs(j3eval[0]) < 0.0000010000000000 )
5927 {
5928 {
5929 IkReal j3array[2], cj3array[2], sj3array[2];
5930 bool j3valid[2]={false};
5931 _nj3 = 2;
5932 CheckValue<IkReal> x460=IKPowWithIntegerCheck(gconst1,-1);
5933 if(!x460.valid){
5934 continue;
5935 }
5936 sj3array[0]=((-1.0)*new_r00*(x460.value));
5937 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
5938 {
5939  j3valid[0] = j3valid[1] = true;
5940  j3array[0] = IKasin(sj3array[0]);
5941  cj3array[0] = IKcos(j3array[0]);
5942  sj3array[1] = sj3array[0];
5943  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
5944  cj3array[1] = -cj3array[0];
5945 }
5946 else if( isnan(sj3array[0]) )
5947 {
5948  // probably any value will work
5949  j3valid[0] = true;
5950  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
5951 }
5952 for(int ij3 = 0; ij3 < 2; ++ij3)
5953 {
5954 if( !j3valid[ij3] )
5955 {
5956  continue;
5957 }
5958 _ij3[0] = ij3; _ij3[1] = -1;
5959 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
5960 {
5961 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5962 {
5963  j3valid[iij3]=false; _ij3[1] = iij3; break;
5964 }
5965 }
5966 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5967 {
5968 IkReal evalcond[6];
5969 IkReal x461=IKcos(j3);
5970 IkReal x462=IKsin(j3);
5971 evalcond[0]=(gconst1*x461);
5972 evalcond[1]=(new_r00*x461);
5973 evalcond[2]=((-1.0)*new_r11*x461);
5974 evalcond[3]=(((new_r00*x462))+gconst1);
5975 evalcond[4]=(((new_r11*x462))+gconst1);
5976 evalcond[5]=(((gconst1*x462))+new_r11);
5977 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5978 {
5979 continue;
5980 }
5981 }
5982 
5983 {
5984 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5985 vinfos[0].jointtype = 1;
5986 vinfos[0].foffset = j0;
5987 vinfos[0].indices[0] = _ij0[0];
5988 vinfos[0].indices[1] = _ij0[1];
5989 vinfos[0].maxsolutions = _nj0;
5990 vinfos[1].jointtype = 1;
5991 vinfos[1].foffset = j1;
5992 vinfos[1].indices[0] = _ij1[0];
5993 vinfos[1].indices[1] = _ij1[1];
5994 vinfos[1].maxsolutions = _nj1;
5995 vinfos[2].jointtype = 1;
5996 vinfos[2].foffset = j2;
5997 vinfos[2].indices[0] = _ij2[0];
5998 vinfos[2].indices[1] = _ij2[1];
5999 vinfos[2].maxsolutions = _nj2;
6000 vinfos[3].jointtype = 1;
6001 vinfos[3].foffset = j3;
6002 vinfos[3].indices[0] = _ij3[0];
6003 vinfos[3].indices[1] = _ij3[1];
6004 vinfos[3].maxsolutions = _nj3;
6005 vinfos[4].jointtype = 1;
6006 vinfos[4].foffset = j4;
6007 vinfos[4].indices[0] = _ij4[0];
6008 vinfos[4].indices[1] = _ij4[1];
6009 vinfos[4].maxsolutions = _nj4;
6010 vinfos[5].jointtype = 1;
6011 vinfos[5].foffset = j5;
6012 vinfos[5].indices[0] = _ij5[0];
6013 vinfos[5].indices[1] = _ij5[1];
6014 vinfos[5].maxsolutions = _nj5;
6015 std::vector<int> vfree(0);
6016 solutions.AddSolution(vinfos,vfree);
6017 }
6018 }
6019 }
6020 
6021 } else
6022 {
6023 {
6024 IkReal j3array[2], cj3array[2], sj3array[2];
6025 bool j3valid[2]={false};
6026 _nj3 = 2;
6027 CheckValue<IkReal> x463=IKPowWithIntegerCheck(new_r11,-1);
6028 if(!x463.valid){
6029 continue;
6030 }
6031 sj3array[0]=((-1.0)*gconst1*(x463.value));
6032 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
6033 {
6034  j3valid[0] = j3valid[1] = true;
6035  j3array[0] = IKasin(sj3array[0]);
6036  cj3array[0] = IKcos(j3array[0]);
6037  sj3array[1] = sj3array[0];
6038  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
6039  cj3array[1] = -cj3array[0];
6040 }
6041 else if( isnan(sj3array[0]) )
6042 {
6043  // probably any value will work
6044  j3valid[0] = true;
6045  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
6046 }
6047 for(int ij3 = 0; ij3 < 2; ++ij3)
6048 {
6049 if( !j3valid[ij3] )
6050 {
6051  continue;
6052 }
6053 _ij3[0] = ij3; _ij3[1] = -1;
6054 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
6055 {
6056 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6057 {
6058  j3valid[iij3]=false; _ij3[1] = iij3; break;
6059 }
6060 }
6061 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6062 {
6063 IkReal evalcond[6];
6064 IkReal x464=IKcos(j3);
6065 IkReal x465=IKsin(j3);
6066 IkReal x466=(gconst1*x465);
6067 evalcond[0]=(gconst1*x464);
6068 evalcond[1]=(new_r00*x464);
6069 evalcond[2]=((-1.0)*new_r11*x464);
6070 evalcond[3]=(((new_r00*x465))+gconst1);
6071 evalcond[4]=(x466+new_r00);
6072 evalcond[5]=(x466+new_r11);
6073 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
6074 {
6075 continue;
6076 }
6077 }
6078 
6079 {
6080 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6081 vinfos[0].jointtype = 1;
6082 vinfos[0].foffset = j0;
6083 vinfos[0].indices[0] = _ij0[0];
6084 vinfos[0].indices[1] = _ij0[1];
6085 vinfos[0].maxsolutions = _nj0;
6086 vinfos[1].jointtype = 1;
6087 vinfos[1].foffset = j1;
6088 vinfos[1].indices[0] = _ij1[0];
6089 vinfos[1].indices[1] = _ij1[1];
6090 vinfos[1].maxsolutions = _nj1;
6091 vinfos[2].jointtype = 1;
6092 vinfos[2].foffset = j2;
6093 vinfos[2].indices[0] = _ij2[0];
6094 vinfos[2].indices[1] = _ij2[1];
6095 vinfos[2].maxsolutions = _nj2;
6096 vinfos[3].jointtype = 1;
6097 vinfos[3].foffset = j3;
6098 vinfos[3].indices[0] = _ij3[0];
6099 vinfos[3].indices[1] = _ij3[1];
6100 vinfos[3].maxsolutions = _nj3;
6101 vinfos[4].jointtype = 1;
6102 vinfos[4].foffset = j4;
6103 vinfos[4].indices[0] = _ij4[0];
6104 vinfos[4].indices[1] = _ij4[1];
6105 vinfos[4].maxsolutions = _nj4;
6106 vinfos[5].jointtype = 1;
6107 vinfos[5].foffset = j5;
6108 vinfos[5].indices[0] = _ij5[0];
6109 vinfos[5].indices[1] = _ij5[1];
6110 vinfos[5].maxsolutions = _nj5;
6111 std::vector<int> vfree(0);
6112 solutions.AddSolution(vinfos,vfree);
6113 }
6114 }
6115 }
6116 
6117 }
6118 
6119 }
6120 
6121 } else
6122 {
6123 {
6124 IkReal j3array[2], cj3array[2], sj3array[2];
6125 bool j3valid[2]={false};
6126 _nj3 = 2;
6127 CheckValue<IkReal> x467=IKPowWithIntegerCheck(new_r00,-1);
6128 if(!x467.valid){
6129 continue;
6130 }
6131 sj3array[0]=((-1.0)*gconst1*(x467.value));
6132 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
6133 {
6134  j3valid[0] = j3valid[1] = true;
6135  j3array[0] = IKasin(sj3array[0]);
6136  cj3array[0] = IKcos(j3array[0]);
6137  sj3array[1] = sj3array[0];
6138  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
6139  cj3array[1] = -cj3array[0];
6140 }
6141 else if( isnan(sj3array[0]) )
6142 {
6143  // probably any value will work
6144  j3valid[0] = true;
6145  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
6146 }
6147 for(int ij3 = 0; ij3 < 2; ++ij3)
6148 {
6149 if( !j3valid[ij3] )
6150 {
6151  continue;
6152 }
6153 _ij3[0] = ij3; _ij3[1] = -1;
6154 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
6155 {
6156 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6157 {
6158  j3valid[iij3]=false; _ij3[1] = iij3; break;
6159 }
6160 }
6161 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6162 {
6163 IkReal evalcond[6];
6164 IkReal x468=IKcos(j3);
6165 IkReal x469=IKsin(j3);
6166 IkReal x470=(gconst1*x469);
6167 evalcond[0]=(gconst1*x468);
6168 evalcond[1]=(new_r00*x468);
6169 evalcond[2]=((-1.0)*new_r11*x468);
6170 evalcond[3]=(((new_r11*x469))+gconst1);
6171 evalcond[4]=(x470+new_r00);
6172 evalcond[5]=(x470+new_r11);
6173 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
6174 {
6175 continue;
6176 }
6177 }
6178 
6179 {
6180 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6181 vinfos[0].jointtype = 1;
6182 vinfos[0].foffset = j0;
6183 vinfos[0].indices[0] = _ij0[0];
6184 vinfos[0].indices[1] = _ij0[1];
6185 vinfos[0].maxsolutions = _nj0;
6186 vinfos[1].jointtype = 1;
6187 vinfos[1].foffset = j1;
6188 vinfos[1].indices[0] = _ij1[0];
6189 vinfos[1].indices[1] = _ij1[1];
6190 vinfos[1].maxsolutions = _nj1;
6191 vinfos[2].jointtype = 1;
6192 vinfos[2].foffset = j2;
6193 vinfos[2].indices[0] = _ij2[0];
6194 vinfos[2].indices[1] = _ij2[1];
6195 vinfos[2].maxsolutions = _nj2;
6196 vinfos[3].jointtype = 1;
6197 vinfos[3].foffset = j3;
6198 vinfos[3].indices[0] = _ij3[0];
6199 vinfos[3].indices[1] = _ij3[1];
6200 vinfos[3].maxsolutions = _nj3;
6201 vinfos[4].jointtype = 1;
6202 vinfos[4].foffset = j4;
6203 vinfos[4].indices[0] = _ij4[0];
6204 vinfos[4].indices[1] = _ij4[1];
6205 vinfos[4].maxsolutions = _nj4;
6206 vinfos[5].jointtype = 1;
6207 vinfos[5].foffset = j5;
6208 vinfos[5].indices[0] = _ij5[0];
6209 vinfos[5].indices[1] = _ij5[1];
6210 vinfos[5].maxsolutions = _nj5;
6211 std::vector<int> vfree(0);
6212 solutions.AddSolution(vinfos,vfree);
6213 }
6214 }
6215 }
6216 
6217 }
6218 
6219 }
6220 
6221 }
6222 } while(0);
6223 if( bgotonextstatement )
6224 {
6225 bool bgotonextstatement = true;
6226 do
6227 {
6228 evalcond[0]=IKabs(new_r11);
6229 if( IKabs(evalcond[0]) < 0.0000050000000000 )
6230 {
6231 bgotonextstatement=false;
6232 {
6233 IkReal j3eval[1];
6234 IkReal x471=((-1.0)*new_r01);
6235 CheckValue<IkReal> x473 = IKatan2WithCheck(IkReal(0),IkReal(x471),IKFAST_ATAN2_MAGTHRESH);
6236 if(!x473.valid){
6237 continue;
6238 }
6239 IkReal x472=((-1.0)*(x473.value));
6240 sj4=0;
6241 cj4=1.0;
6242 j4=0;
6243 sj5=gconst1;
6244 cj5=gconst2;
6245 j5=x472;
6246 new_r11=0;
6247 IkReal gconst0=x472;
6248 IkReal gconst1=0;
6249 IkReal x474 = new_r01*new_r01;
6250 if(IKabs(x474)==0){
6251 continue;
6252 }
6253 IkReal gconst2=(x471*(pow(x474,-0.5)));
6254 j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
6255 if( IKabs(j3eval[0]) < 0.0000010000000000 )
6256 {
6257 {
6258 IkReal j3eval[1];
6259 IkReal x475=((-1.0)*new_r01);
6260 CheckValue<IkReal> x477 = IKatan2WithCheck(IkReal(0),IkReal(x475),IKFAST_ATAN2_MAGTHRESH);
6261 if(!x477.valid){
6262 continue;
6263 }
6264 IkReal x476=((-1.0)*(x477.value));
6265 sj4=0;
6266 cj4=1.0;
6267 j4=0;
6268 sj5=gconst1;
6269 cj5=gconst2;
6270 j5=x476;
6271 new_r11=0;
6272 IkReal gconst0=x476;
6273 IkReal gconst1=0;
6274 IkReal x478 = new_r01*new_r01;
6275 if(IKabs(x478)==0){
6276 continue;
6277 }
6278 IkReal gconst2=(x475*(pow(x478,-0.5)));
6279 j3eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
6280 if( IKabs(j3eval[0]) < 0.0000010000000000 )
6281 {
6282 {
6283 IkReal j3eval[1];
6284 IkReal x479=((-1.0)*new_r01);
6285 CheckValue<IkReal> x481 = IKatan2WithCheck(IkReal(0),IkReal(x479),IKFAST_ATAN2_MAGTHRESH);
6286 if(!x481.valid){
6287 continue;
6288 }
6289 IkReal x480=((-1.0)*(x481.value));
6290 sj4=0;
6291 cj4=1.0;
6292 j4=0;
6293 sj5=gconst1;
6294 cj5=gconst2;
6295 j5=x480;
6296 new_r11=0;
6297 IkReal gconst0=x480;
6298 IkReal gconst1=0;
6299 IkReal x482 = new_r01*new_r01;
6300 if(IKabs(x482)==0){
6301 continue;
6302 }
6303 IkReal gconst2=(x479*(pow(x482,-0.5)));
6304 j3eval[0]=new_r01;
6305 if( IKabs(j3eval[0]) < 0.0000010000000000 )
6306 {
6307 continue; // 3 cases reached
6308 
6309 } else
6310 {
6311 {
6312 IkReal j3array[1], cj3array[1], sj3array[1];
6313 bool j3valid[1]={false};
6314 _nj3 = 1;
6315 CheckValue<IkReal> x483=IKPowWithIntegerCheck(new_r01,-1);
6316 if(!x483.valid){
6317 continue;
6318 }
6319 CheckValue<IkReal> x484=IKPowWithIntegerCheck(gconst2,-1);
6320 if(!x484.valid){
6321 continue;
6322 }
6323 if( IKabs(((-1.0)*gconst2*(x483.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r00*(x484.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst2*(x483.value)))+IKsqr((new_r00*(x484.value)))-1) <= IKFAST_SINCOS_THRESH )
6324  continue;
6325 j3array[0]=IKatan2(((-1.0)*gconst2*(x483.value)), (new_r00*(x484.value)));
6326 sj3array[0]=IKsin(j3array[0]);
6327 cj3array[0]=IKcos(j3array[0]);
6328 if( j3array[0] > IKPI )
6329 {
6330  j3array[0]-=IK2PI;
6331 }
6332 else if( j3array[0] < -IKPI )
6333 { j3array[0]+=IK2PI;
6334 }
6335 j3valid[0] = true;
6336 for(int ij3 = 0; ij3 < 1; ++ij3)
6337 {
6338 if( !j3valid[ij3] )
6339 {
6340  continue;
6341 }
6342 _ij3[0] = ij3; _ij3[1] = -1;
6343 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6344 {
6345 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6346 {
6347  j3valid[iij3]=false; _ij3[1] = iij3; break;
6348 }
6349 }
6350 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6351 {
6352 IkReal evalcond[8];
6353 IkReal x485=IKcos(j3);
6354 IkReal x486=IKsin(j3);
6355 IkReal x487=((1.0)*gconst2);
6356 IkReal x488=(gconst2*x486);
6357 evalcond[0]=(new_r01*x485);
6358 evalcond[1]=((-1.0)*gconst2*x485);
6359 evalcond[2]=(gconst2+((new_r01*x486)));
6360 evalcond[3]=(x488+new_r01);
6361 evalcond[4]=(new_r00+(((-1.0)*x485*x487)));
6362 evalcond[5]=((((-1.0)*x486*x487))+new_r10);
6363 evalcond[6]=((((-1.0)*new_r10*x485))+((new_r00*x486)));
6364 evalcond[7]=((((-1.0)*x487))+((new_r10*x486))+((new_r00*x485)));
6365 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
6366 {
6367 continue;
6368 }
6369 }
6370 
6371 {
6372 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6373 vinfos[0].jointtype = 1;
6374 vinfos[0].foffset = j0;
6375 vinfos[0].indices[0] = _ij0[0];
6376 vinfos[0].indices[1] = _ij0[1];
6377 vinfos[0].maxsolutions = _nj0;
6378 vinfos[1].jointtype = 1;
6379 vinfos[1].foffset = j1;
6380 vinfos[1].indices[0] = _ij1[0];
6381 vinfos[1].indices[1] = _ij1[1];
6382 vinfos[1].maxsolutions = _nj1;
6383 vinfos[2].jointtype = 1;
6384 vinfos[2].foffset = j2;
6385 vinfos[2].indices[0] = _ij2[0];
6386 vinfos[2].indices[1] = _ij2[1];
6387 vinfos[2].maxsolutions = _nj2;
6388 vinfos[3].jointtype = 1;
6389 vinfos[3].foffset = j3;
6390 vinfos[3].indices[0] = _ij3[0];
6391 vinfos[3].indices[1] = _ij3[1];
6392 vinfos[3].maxsolutions = _nj3;
6393 vinfos[4].jointtype = 1;
6394 vinfos[4].foffset = j4;
6395 vinfos[4].indices[0] = _ij4[0];
6396 vinfos[4].indices[1] = _ij4[1];
6397 vinfos[4].maxsolutions = _nj4;
6398 vinfos[5].jointtype = 1;
6399 vinfos[5].foffset = j5;
6400 vinfos[5].indices[0] = _ij5[0];
6401 vinfos[5].indices[1] = _ij5[1];
6402 vinfos[5].maxsolutions = _nj5;
6403 std::vector<int> vfree(0);
6404 solutions.AddSolution(vinfos,vfree);
6405 }
6406 }
6407 }
6408 
6409 }
6410 
6411 }
6412 
6413 } else
6414 {
6415 {
6416 IkReal j3array[1], cj3array[1], sj3array[1];
6417 bool j3valid[1]={false};
6418 _nj3 = 1;
6419 CheckValue<IkReal> x489 = IKatan2WithCheck(IkReal(((-1.0)*new_r01)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
6420 if(!x489.valid){
6421 continue;
6422 }
6424 if(!x490.valid){
6425 continue;
6426 }
6427 j3array[0]=((-1.5707963267949)+(x489.value)+(((1.5707963267949)*(x490.value))));
6428 sj3array[0]=IKsin(j3array[0]);
6429 cj3array[0]=IKcos(j3array[0]);
6430 if( j3array[0] > IKPI )
6431 {
6432  j3array[0]-=IK2PI;
6433 }
6434 else if( j3array[0] < -IKPI )
6435 { j3array[0]+=IK2PI;
6436 }
6437 j3valid[0] = true;
6438 for(int ij3 = 0; ij3 < 1; ++ij3)
6439 {
6440 if( !j3valid[ij3] )
6441 {
6442  continue;
6443 }
6444 _ij3[0] = ij3; _ij3[1] = -1;
6445 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6446 {
6447 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6448 {
6449  j3valid[iij3]=false; _ij3[1] = iij3; break;
6450 }
6451 }
6452 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6453 {
6454 IkReal evalcond[8];
6455 IkReal x491=IKcos(j3);
6456 IkReal x492=IKsin(j3);
6457 IkReal x493=((1.0)*gconst2);
6458 IkReal x494=(gconst2*x492);
6459 evalcond[0]=(new_r01*x491);
6460 evalcond[1]=((-1.0)*gconst2*x491);
6461 evalcond[2]=(gconst2+((new_r01*x492)));
6462 evalcond[3]=(x494+new_r01);
6463 evalcond[4]=((((-1.0)*x491*x493))+new_r00);
6464 evalcond[5]=(new_r10+(((-1.0)*x492*x493)));
6465 evalcond[6]=((((-1.0)*new_r10*x491))+((new_r00*x492)));
6466 evalcond[7]=((((-1.0)*x493))+((new_r10*x492))+((new_r00*x491)));
6467 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
6468 {
6469 continue;
6470 }
6471 }
6472 
6473 {
6474 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6475 vinfos[0].jointtype = 1;
6476 vinfos[0].foffset = j0;
6477 vinfos[0].indices[0] = _ij0[0];
6478 vinfos[0].indices[1] = _ij0[1];
6479 vinfos[0].maxsolutions = _nj0;
6480 vinfos[1].jointtype = 1;
6481 vinfos[1].foffset = j1;
6482 vinfos[1].indices[0] = _ij1[0];
6483 vinfos[1].indices[1] = _ij1[1];
6484 vinfos[1].maxsolutions = _nj1;
6485 vinfos[2].jointtype = 1;
6486 vinfos[2].foffset = j2;
6487 vinfos[2].indices[0] = _ij2[0];
6488 vinfos[2].indices[1] = _ij2[1];
6489 vinfos[2].maxsolutions = _nj2;
6490 vinfos[3].jointtype = 1;
6491 vinfos[3].foffset = j3;
6492 vinfos[3].indices[0] = _ij3[0];
6493 vinfos[3].indices[1] = _ij3[1];
6494 vinfos[3].maxsolutions = _nj3;
6495 vinfos[4].jointtype = 1;
6496 vinfos[4].foffset = j4;
6497 vinfos[4].indices[0] = _ij4[0];
6498 vinfos[4].indices[1] = _ij4[1];
6499 vinfos[4].maxsolutions = _nj4;
6500 vinfos[5].jointtype = 1;
6501 vinfos[5].foffset = j5;
6502 vinfos[5].indices[0] = _ij5[0];
6503 vinfos[5].indices[1] = _ij5[1];
6504 vinfos[5].maxsolutions = _nj5;
6505 std::vector<int> vfree(0);
6506 solutions.AddSolution(vinfos,vfree);
6507 }
6508 }
6509 }
6510 
6511 }
6512 
6513 }
6514 
6515 } else
6516 {
6517 {
6518 IkReal j3array[1], cj3array[1], sj3array[1];
6519 bool j3valid[1]={false};
6520 _nj3 = 1;
6522 if(!x495.valid){
6523 continue;
6524 }
6525 CheckValue<IkReal> x496 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
6526 if(!x496.valid){
6527 continue;
6528 }
6529 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x495.value)))+(x496.value));
6530 sj3array[0]=IKsin(j3array[0]);
6531 cj3array[0]=IKcos(j3array[0]);
6532 if( j3array[0] > IKPI )
6533 {
6534  j3array[0]-=IK2PI;
6535 }
6536 else if( j3array[0] < -IKPI )
6537 { j3array[0]+=IK2PI;
6538 }
6539 j3valid[0] = true;
6540 for(int ij3 = 0; ij3 < 1; ++ij3)
6541 {
6542 if( !j3valid[ij3] )
6543 {
6544  continue;
6545 }
6546 _ij3[0] = ij3; _ij3[1] = -1;
6547 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6548 {
6549 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6550 {
6551  j3valid[iij3]=false; _ij3[1] = iij3; break;
6552 }
6553 }
6554 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6555 {
6556 IkReal evalcond[8];
6557 IkReal x497=IKcos(j3);
6558 IkReal x498=IKsin(j3);
6559 IkReal x499=((1.0)*gconst2);
6560 IkReal x500=(gconst2*x498);
6561 evalcond[0]=(new_r01*x497);
6562 evalcond[1]=((-1.0)*gconst2*x497);
6563 evalcond[2]=(gconst2+((new_r01*x498)));
6564 evalcond[3]=(x500+new_r01);
6565 evalcond[4]=((((-1.0)*x497*x499))+new_r00);
6566 evalcond[5]=((((-1.0)*x498*x499))+new_r10);
6567 evalcond[6]=((((-1.0)*new_r10*x497))+((new_r00*x498)));
6568 evalcond[7]=((((-1.0)*x499))+((new_r10*x498))+((new_r00*x497)));
6569 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
6570 {
6571 continue;
6572 }
6573 }
6574 
6575 {
6576 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6577 vinfos[0].jointtype = 1;
6578 vinfos[0].foffset = j0;
6579 vinfos[0].indices[0] = _ij0[0];
6580 vinfos[0].indices[1] = _ij0[1];
6581 vinfos[0].maxsolutions = _nj0;
6582 vinfos[1].jointtype = 1;
6583 vinfos[1].foffset = j1;
6584 vinfos[1].indices[0] = _ij1[0];
6585 vinfos[1].indices[1] = _ij1[1];
6586 vinfos[1].maxsolutions = _nj1;
6587 vinfos[2].jointtype = 1;
6588 vinfos[2].foffset = j2;
6589 vinfos[2].indices[0] = _ij2[0];
6590 vinfos[2].indices[1] = _ij2[1];
6591 vinfos[2].maxsolutions = _nj2;
6592 vinfos[3].jointtype = 1;
6593 vinfos[3].foffset = j3;
6594 vinfos[3].indices[0] = _ij3[0];
6595 vinfos[3].indices[1] = _ij3[1];
6596 vinfos[3].maxsolutions = _nj3;
6597 vinfos[4].jointtype = 1;
6598 vinfos[4].foffset = j4;
6599 vinfos[4].indices[0] = _ij4[0];
6600 vinfos[4].indices[1] = _ij4[1];
6601 vinfos[4].maxsolutions = _nj4;
6602 vinfos[5].jointtype = 1;
6603 vinfos[5].foffset = j5;
6604 vinfos[5].indices[0] = _ij5[0];
6605 vinfos[5].indices[1] = _ij5[1];
6606 vinfos[5].maxsolutions = _nj5;
6607 std::vector<int> vfree(0);
6608 solutions.AddSolution(vinfos,vfree);
6609 }
6610 }
6611 }
6612 
6613 }
6614 
6615 }
6616 
6617 }
6618 } while(0);
6619 if( bgotonextstatement )
6620 {
6621 bool bgotonextstatement = true;
6622 do
6623 {
6624 if( 1 )
6625 {
6626 bgotonextstatement=false;
6627 continue; // branch miss [j3]
6628 
6629 }
6630 } while(0);
6631 if( bgotonextstatement )
6632 {
6633 }
6634 }
6635 }
6636 }
6637 }
6638 }
6639 
6640 } else
6641 {
6642 {
6643 IkReal j3array[1], cj3array[1], sj3array[1];
6644 bool j3valid[1]={false};
6645 _nj3 = 1;
6646 IkReal x501=((1.0)*new_r01);
6647 CheckValue<IkReal> x502 = IKatan2WithCheck(IkReal(((new_r01*new_r01)+(((-1.0)*(gconst1*gconst1))))),IkReal(((((-1.0)*new_r11*x501))+((gconst1*gconst2)))),IKFAST_ATAN2_MAGTHRESH);
6648 if(!x502.valid){
6649 continue;
6650 }
6651 CheckValue<IkReal> x503=IKPowWithIntegerCheck(IKsign((((gconst1*new_r11))+(((-1.0)*gconst2*x501)))),-1);
6652 if(!x503.valid){
6653 continue;
6654 }
6655 j3array[0]=((-1.5707963267949)+(x502.value)+(((1.5707963267949)*(x503.value))));
6656 sj3array[0]=IKsin(j3array[0]);
6657 cj3array[0]=IKcos(j3array[0]);
6658 if( j3array[0] > IKPI )
6659 {
6660  j3array[0]-=IK2PI;
6661 }
6662 else if( j3array[0] < -IKPI )
6663 { j3array[0]+=IK2PI;
6664 }
6665 j3valid[0] = true;
6666 for(int ij3 = 0; ij3 < 1; ++ij3)
6667 {
6668 if( !j3valid[ij3] )
6669 {
6670  continue;
6671 }
6672 _ij3[0] = ij3; _ij3[1] = -1;
6673 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6674 {
6675 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6676 {
6677  j3valid[iij3]=false; _ij3[1] = iij3; break;
6678 }
6679 }
6680 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6681 {
6682 IkReal evalcond[8];
6683 IkReal x504=IKcos(j3);
6684 IkReal x505=IKsin(j3);
6685 IkReal x506=((1.0)*gconst2);
6686 IkReal x507=(gconst1*x505);
6687 IkReal x508=(gconst2*x505);
6688 IkReal x509=(gconst1*x504);
6689 IkReal x510=((1.0)*x504);
6690 IkReal x511=(x504*x506);
6691 evalcond[0]=(gconst1+((new_r11*x505))+((new_r01*x504)));
6692 evalcond[1]=(x508+x509+new_r01);
6693 evalcond[2]=((((-1.0)*new_r10*x510))+gconst1+((new_r00*x505)));
6694 evalcond[3]=((((-1.0)*new_r11*x510))+gconst2+((new_r01*x505)));
6695 evalcond[4]=(x507+new_r00+(((-1.0)*x511)));
6696 evalcond[5]=(x507+new_r11+(((-1.0)*x511)));
6697 evalcond[6]=((((-1.0)*x506))+((new_r10*x505))+((new_r00*x504)));
6698 evalcond[7]=((((-1.0)*x505*x506))+new_r10+(((-1.0)*x509)));
6699 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
6700 {
6701 continue;
6702 }
6703 }
6704 
6705 {
6706 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6707 vinfos[0].jointtype = 1;
6708 vinfos[0].foffset = j0;
6709 vinfos[0].indices[0] = _ij0[0];
6710 vinfos[0].indices[1] = _ij0[1];
6711 vinfos[0].maxsolutions = _nj0;
6712 vinfos[1].jointtype = 1;
6713 vinfos[1].foffset = j1;
6714 vinfos[1].indices[0] = _ij1[0];
6715 vinfos[1].indices[1] = _ij1[1];
6716 vinfos[1].maxsolutions = _nj1;
6717 vinfos[2].jointtype = 1;
6718 vinfos[2].foffset = j2;
6719 vinfos[2].indices[0] = _ij2[0];
6720 vinfos[2].indices[1] = _ij2[1];
6721 vinfos[2].maxsolutions = _nj2;
6722 vinfos[3].jointtype = 1;
6723 vinfos[3].foffset = j3;
6724 vinfos[3].indices[0] = _ij3[0];
6725 vinfos[3].indices[1] = _ij3[1];
6726 vinfos[3].maxsolutions = _nj3;
6727 vinfos[4].jointtype = 1;
6728 vinfos[4].foffset = j4;
6729 vinfos[4].indices[0] = _ij4[0];
6730 vinfos[4].indices[1] = _ij4[1];
6731 vinfos[4].maxsolutions = _nj4;
6732 vinfos[5].jointtype = 1;
6733 vinfos[5].foffset = j5;
6734 vinfos[5].indices[0] = _ij5[0];
6735 vinfos[5].indices[1] = _ij5[1];
6736 vinfos[5].maxsolutions = _nj5;
6737 std::vector<int> vfree(0);
6738 solutions.AddSolution(vinfos,vfree);
6739 }
6740 }
6741 }
6742 
6743 }
6744 
6745 }
6746 
6747 } else
6748 {
6749 {
6750 IkReal j3array[1], cj3array[1], sj3array[1];
6751 bool j3valid[1]={false};
6752 _nj3 = 1;
6753 IkReal x512=((1.0)*gconst2);
6754 CheckValue<IkReal> x513 = IKatan2WithCheck(IkReal(((gconst1*gconst1)+((new_r01*new_r10)))),IkReal((((new_r00*new_r01))+(((-1.0)*gconst1*x512)))),IKFAST_ATAN2_MAGTHRESH);
6755 if(!x513.valid){
6756 continue;
6757 }
6758 CheckValue<IkReal> x514=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x512))+(((-1.0)*gconst1*new_r00)))),-1);
6759 if(!x514.valid){
6760 continue;
6761 }
6762 j3array[0]=((-1.5707963267949)+(x513.value)+(((1.5707963267949)*(x514.value))));
6763 sj3array[0]=IKsin(j3array[0]);
6764 cj3array[0]=IKcos(j3array[0]);
6765 if( j3array[0] > IKPI )
6766 {
6767  j3array[0]-=IK2PI;
6768 }
6769 else if( j3array[0] < -IKPI )
6770 { j3array[0]+=IK2PI;
6771 }
6772 j3valid[0] = true;
6773 for(int ij3 = 0; ij3 < 1; ++ij3)
6774 {
6775 if( !j3valid[ij3] )
6776 {
6777  continue;
6778 }
6779 _ij3[0] = ij3; _ij3[1] = -1;
6780 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6781 {
6782 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6783 {
6784  j3valid[iij3]=false; _ij3[1] = iij3; break;
6785 }
6786 }
6787 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6788 {
6789 IkReal evalcond[8];
6790 IkReal x515=IKcos(j3);
6791 IkReal x516=IKsin(j3);
6792 IkReal x517=((1.0)*gconst2);
6793 IkReal x518=(gconst1*x516);
6794 IkReal x519=(gconst2*x516);
6795 IkReal x520=(gconst1*x515);
6796 IkReal x521=((1.0)*x515);
6797 IkReal x522=(x515*x517);
6798 evalcond[0]=(((new_r01*x515))+((new_r11*x516))+gconst1);
6799 evalcond[1]=(x520+x519+new_r01);
6800 evalcond[2]=(((new_r00*x516))+gconst1+(((-1.0)*new_r10*x521)));
6801 evalcond[3]=(((new_r01*x516))+gconst2+(((-1.0)*new_r11*x521)));
6802 evalcond[4]=((((-1.0)*x522))+x518+new_r00);
6803 evalcond[5]=((((-1.0)*x522))+x518+new_r11);
6804 evalcond[6]=(((new_r00*x515))+((new_r10*x516))+(((-1.0)*x517)));
6805 evalcond[7]=((((-1.0)*x520))+(((-1.0)*x516*x517))+new_r10);
6806 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
6807 {
6808 continue;
6809 }
6810 }
6811 
6812 {
6813 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6814 vinfos[0].jointtype = 1;
6815 vinfos[0].foffset = j0;
6816 vinfos[0].indices[0] = _ij0[0];
6817 vinfos[0].indices[1] = _ij0[1];
6818 vinfos[0].maxsolutions = _nj0;
6819 vinfos[1].jointtype = 1;
6820 vinfos[1].foffset = j1;
6821 vinfos[1].indices[0] = _ij1[0];
6822 vinfos[1].indices[1] = _ij1[1];
6823 vinfos[1].maxsolutions = _nj1;
6824 vinfos[2].jointtype = 1;
6825 vinfos[2].foffset = j2;
6826 vinfos[2].indices[0] = _ij2[0];
6827 vinfos[2].indices[1] = _ij2[1];
6828 vinfos[2].maxsolutions = _nj2;
6829 vinfos[3].jointtype = 1;
6830 vinfos[3].foffset = j3;
6831 vinfos[3].indices[0] = _ij3[0];
6832 vinfos[3].indices[1] = _ij3[1];
6833 vinfos[3].maxsolutions = _nj3;
6834 vinfos[4].jointtype = 1;
6835 vinfos[4].foffset = j4;
6836 vinfos[4].indices[0] = _ij4[0];
6837 vinfos[4].indices[1] = _ij4[1];
6838 vinfos[4].maxsolutions = _nj4;
6839 vinfos[5].jointtype = 1;
6840 vinfos[5].foffset = j5;
6841 vinfos[5].indices[0] = _ij5[0];
6842 vinfos[5].indices[1] = _ij5[1];
6843 vinfos[5].maxsolutions = _nj5;
6844 std::vector<int> vfree(0);
6845 solutions.AddSolution(vinfos,vfree);
6846 }
6847 }
6848 }
6849 
6850 }
6851 
6852 }
6853 
6854 } else
6855 {
6856 {
6857 IkReal j3array[1], cj3array[1], sj3array[1];
6858 bool j3valid[1]={false};
6859 _nj3 = 1;
6860 IkReal x523=((1.0)*new_r11);
6861 CheckValue<IkReal> x524 = IKatan2WithCheck(IkReal((((gconst1*new_r10))+((gconst1*new_r01)))),IkReal((((gconst1*new_r00))+(((-1.0)*gconst1*x523)))),IKFAST_ATAN2_MAGTHRESH);
6862 if(!x524.valid){
6863 continue;
6864 }
6865 CheckValue<IkReal> x525=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x523))+(((-1.0)*new_r00*new_r01)))),-1);
6866 if(!x525.valid){
6867 continue;
6868 }
6869 j3array[0]=((-1.5707963267949)+(x524.value)+(((1.5707963267949)*(x525.value))));
6870 sj3array[0]=IKsin(j3array[0]);
6871 cj3array[0]=IKcos(j3array[0]);
6872 if( j3array[0] > IKPI )
6873 {
6874  j3array[0]-=IK2PI;
6875 }
6876 else if( j3array[0] < -IKPI )
6877 { j3array[0]+=IK2PI;
6878 }
6879 j3valid[0] = true;
6880 for(int ij3 = 0; ij3 < 1; ++ij3)
6881 {
6882 if( !j3valid[ij3] )
6883 {
6884  continue;
6885 }
6886 _ij3[0] = ij3; _ij3[1] = -1;
6887 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6888 {
6889 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6890 {
6891  j3valid[iij3]=false; _ij3[1] = iij3; break;
6892 }
6893 }
6894 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6895 {
6896 IkReal evalcond[8];
6897 IkReal x526=IKcos(j3);
6898 IkReal x527=IKsin(j3);
6899 IkReal x528=((1.0)*gconst2);
6900 IkReal x529=(gconst1*x527);
6901 IkReal x530=(gconst2*x527);
6902 IkReal x531=(gconst1*x526);
6903 IkReal x532=((1.0)*x526);
6904 IkReal x533=(x526*x528);
6905 evalcond[0]=(((new_r01*x526))+gconst1+((new_r11*x527)));
6906 evalcond[1]=(x531+x530+new_r01);
6907 evalcond[2]=(gconst1+(((-1.0)*new_r10*x532))+((new_r00*x527)));
6908 evalcond[3]=(((new_r01*x527))+gconst2+(((-1.0)*new_r11*x532)));
6909 evalcond[4]=((((-1.0)*x533))+x529+new_r00);
6910 evalcond[5]=((((-1.0)*x533))+x529+new_r11);
6911 evalcond[6]=((((-1.0)*x528))+((new_r10*x527))+((new_r00*x526)));
6912 evalcond[7]=((((-1.0)*x527*x528))+(((-1.0)*x531))+new_r10);
6913 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
6914 {
6915 continue;
6916 }
6917 }
6918 
6919 {
6920 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6921 vinfos[0].jointtype = 1;
6922 vinfos[0].foffset = j0;
6923 vinfos[0].indices[0] = _ij0[0];
6924 vinfos[0].indices[1] = _ij0[1];
6925 vinfos[0].maxsolutions = _nj0;
6926 vinfos[1].jointtype = 1;
6927 vinfos[1].foffset = j1;
6928 vinfos[1].indices[0] = _ij1[0];
6929 vinfos[1].indices[1] = _ij1[1];
6930 vinfos[1].maxsolutions = _nj1;
6931 vinfos[2].jointtype = 1;
6932 vinfos[2].foffset = j2;
6933 vinfos[2].indices[0] = _ij2[0];
6934 vinfos[2].indices[1] = _ij2[1];
6935 vinfos[2].maxsolutions = _nj2;
6936 vinfos[3].jointtype = 1;
6937 vinfos[3].foffset = j3;
6938 vinfos[3].indices[0] = _ij3[0];
6939 vinfos[3].indices[1] = _ij3[1];
6940 vinfos[3].maxsolutions = _nj3;
6941 vinfos[4].jointtype = 1;
6942 vinfos[4].foffset = j4;
6943 vinfos[4].indices[0] = _ij4[0];
6944 vinfos[4].indices[1] = _ij4[1];
6945 vinfos[4].maxsolutions = _nj4;
6946 vinfos[5].jointtype = 1;
6947 vinfos[5].foffset = j5;
6948 vinfos[5].indices[0] = _ij5[0];
6949 vinfos[5].indices[1] = _ij5[1];
6950 vinfos[5].maxsolutions = _nj5;
6951 std::vector<int> vfree(0);
6952 solutions.AddSolution(vinfos,vfree);
6953 }
6954 }
6955 }
6956 
6957 }
6958 
6959 }
6960 
6961 }
6962 } while(0);
6963 if( bgotonextstatement )
6964 {
6965 bool bgotonextstatement = true;
6966 do
6967 {
6968 IkReal x534=((-1.0)*new_r11);
6969 IkReal x536 = ((new_r01*new_r01)+(new_r11*new_r11));
6970 if(IKabs(x536)==0){
6971 continue;
6972 }
6973 IkReal x535=pow(x536,-0.5);
6974 CheckValue<IkReal> x537 = IKatan2WithCheck(IkReal(x534),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
6975 if(!x537.valid){
6976 continue;
6977 }
6978 IkReal gconst3=((3.14159265358979)+(((-1.0)*(x537.value))));
6979 IkReal gconst4=(x534*x535);
6980 IkReal gconst5=((1.0)*new_r01*x535);
6981 CheckValue<IkReal> x538 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
6982 if(!x538.valid){
6983 continue;
6984 }
6985 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x538.value)+j5)))), 6.28318530717959)));
6986 if( IKabs(evalcond[0]) < 0.0000050000000000 )
6987 {
6988 bgotonextstatement=false;
6989 {
6990 IkReal j3eval[3];
6991 IkReal x539=((-1.0)*new_r11);
6992 CheckValue<IkReal> x542 = IKatan2WithCheck(IkReal(x539),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
6993 if(!x542.valid){
6994 continue;
6995 }
6996 IkReal x540=((1.0)*(x542.value));
6997 IkReal x541=x535;
6998 sj4=0;
6999 cj4=1.0;
7000 j4=0;
7001 sj5=gconst4;
7002 cj5=gconst5;
7003 j5=((3.14159265)+(((-1.0)*x540)));
7004 IkReal gconst3=((3.14159265358979)+(((-1.0)*x540)));
7005 IkReal gconst4=(x539*x541);
7006 IkReal gconst5=((1.0)*new_r01*x541);
7007 IkReal x543=new_r11*new_r11;
7008 IkReal x544=((1.0)*new_r01);
7009 IkReal x545=((1.0)*new_r10);
7010 IkReal x546=((((-1.0)*new_r00*x544))+(((-1.0)*new_r11*x545)));
7011 IkReal x547=x535;
7012 IkReal x548=(new_r11*x547);
7013 j3eval[0]=x546;
7014 j3eval[1]=((IKabs((((x543*x547))+(((-1.0)*new_r00*x548)))))+(IKabs(((((-1.0)*x544*x548))+(((-1.0)*x545*x548))))));
7015 j3eval[2]=IKsign(x546);
7016 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
7017 {
7018 {
7019 IkReal j3eval[1];
7020 IkReal x549=((-1.0)*new_r11);
7021 CheckValue<IkReal> x552 = IKatan2WithCheck(IkReal(x549),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7022 if(!x552.valid){
7023 continue;
7024 }
7025 IkReal x550=((1.0)*(x552.value));
7026 IkReal x551=x535;
7027 sj4=0;
7028 cj4=1.0;
7029 j4=0;
7030 sj5=gconst4;
7031 cj5=gconst5;
7032 j5=((3.14159265)+(((-1.0)*x550)));
7033 IkReal gconst3=((3.14159265358979)+(((-1.0)*x550)));
7034 IkReal gconst4=(x549*x551);
7035 IkReal gconst5=((1.0)*new_r01*x551);
7036 IkReal x553=new_r11*new_r11;
7037 IkReal x554=new_r01*new_r01*new_r01;
7038 CheckValue<IkReal> x558=IKPowWithIntegerCheck(((new_r01*new_r01)+x553),-1);
7039 if(!x558.valid){
7040 continue;
7041 }
7042 IkReal x555=x558.value;
7043 IkReal x556=(x553*x555);
7044 IkReal x557=(x554*x555);
7045 j3eval[0]=((IKabs((((new_r10*x557))+x556+((new_r01*new_r10*x556)))))+(IKabs((((new_r00*new_r01*x556))+((new_r01*new_r11*x555))+((new_r00*x557))))));
7046 if( IKabs(j3eval[0]) < 0.0000010000000000 )
7047 {
7048 {
7049 IkReal j3eval[1];
7050 IkReal x559=((-1.0)*new_r11);
7051 CheckValue<IkReal> x562 = IKatan2WithCheck(IkReal(x559),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7052 if(!x562.valid){
7053 continue;
7054 }
7055 IkReal x560=((1.0)*(x562.value));
7056 IkReal x561=x535;
7057 sj4=0;
7058 cj4=1.0;
7059 j4=0;
7060 sj5=gconst4;
7061 cj5=gconst5;
7062 j5=((3.14159265)+(((-1.0)*x560)));
7063 IkReal gconst3=((3.14159265358979)+(((-1.0)*x560)));
7064 IkReal gconst4=(x559*x561);
7065 IkReal gconst5=((1.0)*new_r01*x561);
7066 IkReal x563=new_r01*new_r01;
7067 IkReal x564=new_r11*new_r11;
7068 CheckValue<IkReal> x571=IKPowWithIntegerCheck((x564+x563),-1);
7069 if(!x571.valid){
7070 continue;
7071 }
7072 IkReal x565=x571.value;
7073 IkReal x566=(x564*x565);
7074 CheckValue<IkReal> x572=IKPowWithIntegerCheck(((((-1.0)*x563))+(((-1.0)*x564))),-1);
7075 if(!x572.valid){
7076 continue;
7077 }
7078 IkReal x567=x572.value;
7079 IkReal x568=((1.0)*x567);
7080 IkReal x569=(new_r11*x568);
7081 IkReal x570=(new_r01*x568);
7082 j3eval[0]=((IKabs((((x563*x566))+((x565*(x563*x563)))+(((-1.0)*x566)))))+(IKabs(((((-1.0)*new_r01*x569*(new_r11*new_r11)))+(((-1.0)*x569*(new_r01*new_r01*new_r01)))+(((-1.0)*new_r01*x569))))));
7083 if( IKabs(j3eval[0]) < 0.0000010000000000 )
7084 {
7085 {
7086 IkReal evalcond[3];
7087 bool bgotonextstatement = true;
7088 do
7089 {
7090 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
7091 if( IKabs(evalcond[0]) < 0.0000050000000000 )
7092 {
7093 bgotonextstatement=false;
7094 {
7095 IkReal j3array[2], cj3array[2], sj3array[2];
7096 bool j3valid[2]={false};
7097 _nj3 = 2;
7098 CheckValue<IkReal> x573=IKPowWithIntegerCheck(gconst5,-1);
7099 if(!x573.valid){
7100 continue;
7101 }
7102 sj3array[0]=(new_r10*(x573.value));
7103 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
7104 {
7105  j3valid[0] = j3valid[1] = true;
7106  j3array[0] = IKasin(sj3array[0]);
7107  cj3array[0] = IKcos(j3array[0]);
7108  sj3array[1] = sj3array[0];
7109  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
7110  cj3array[1] = -cj3array[0];
7111 }
7112 else if( isnan(sj3array[0]) )
7113 {
7114  // probably any value will work
7115  j3valid[0] = true;
7116  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
7117 }
7118 for(int ij3 = 0; ij3 < 2; ++ij3)
7119 {
7120 if( !j3valid[ij3] )
7121 {
7122  continue;
7123 }
7124 _ij3[0] = ij3; _ij3[1] = -1;
7125 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
7126 {
7127 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
7128 {
7129  j3valid[iij3]=false; _ij3[1] = iij3; break;
7130 }
7131 }
7132 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
7133 {
7134 IkReal evalcond[6];
7135 IkReal x574=IKcos(j3);
7136 IkReal x575=IKsin(j3);
7137 IkReal x576=((-1.0)*x574);
7138 evalcond[0]=(new_r01*x574);
7139 evalcond[1]=(new_r10*x576);
7140 evalcond[2]=(gconst5*x576);
7141 evalcond[3]=(((new_r01*x575))+gconst5);
7142 evalcond[4]=(((gconst5*x575))+new_r01);
7143 evalcond[5]=(((new_r10*x575))+(((-1.0)*gconst5)));
7144 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7145 {
7146 continue;
7147 }
7148 }
7149 
7150 {
7151 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7152 vinfos[0].jointtype = 1;
7153 vinfos[0].foffset = j0;
7154 vinfos[0].indices[0] = _ij0[0];
7155 vinfos[0].indices[1] = _ij0[1];
7156 vinfos[0].maxsolutions = _nj0;
7157 vinfos[1].jointtype = 1;
7158 vinfos[1].foffset = j1;
7159 vinfos[1].indices[0] = _ij1[0];
7160 vinfos[1].indices[1] = _ij1[1];
7161 vinfos[1].maxsolutions = _nj1;
7162 vinfos[2].jointtype = 1;
7163 vinfos[2].foffset = j2;
7164 vinfos[2].indices[0] = _ij2[0];
7165 vinfos[2].indices[1] = _ij2[1];
7166 vinfos[2].maxsolutions = _nj2;
7167 vinfos[3].jointtype = 1;
7168 vinfos[3].foffset = j3;
7169 vinfos[3].indices[0] = _ij3[0];
7170 vinfos[3].indices[1] = _ij3[1];
7171 vinfos[3].maxsolutions = _nj3;
7172 vinfos[4].jointtype = 1;
7173 vinfos[4].foffset = j4;
7174 vinfos[4].indices[0] = _ij4[0];
7175 vinfos[4].indices[1] = _ij4[1];
7176 vinfos[4].maxsolutions = _nj4;
7177 vinfos[5].jointtype = 1;
7178 vinfos[5].foffset = j5;
7179 vinfos[5].indices[0] = _ij5[0];
7180 vinfos[5].indices[1] = _ij5[1];
7181 vinfos[5].maxsolutions = _nj5;
7182 std::vector<int> vfree(0);
7183 solutions.AddSolution(vinfos,vfree);
7184 }
7185 }
7186 }
7187 
7188 }
7189 } while(0);
7190 if( bgotonextstatement )
7191 {
7192 bool bgotonextstatement = true;
7193 do
7194 {
7195 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
7196 evalcond[1]=gconst4;
7197 evalcond[2]=gconst5;
7198 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
7199 {
7200 bgotonextstatement=false;
7201 {
7202 IkReal j3eval[3];
7203 IkReal x577=((-1.0)*new_r11);
7204 CheckValue<IkReal> x579 = IKatan2WithCheck(IkReal(x577),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7205 if(!x579.valid){
7206 continue;
7207 }
7208 IkReal x578=((1.0)*(x579.value));
7209 sj4=0;
7210 cj4=1.0;
7211 j4=0;
7212 sj5=gconst4;
7213 cj5=gconst5;
7214 j5=((3.14159265)+(((-1.0)*x578)));
7215 new_r00=0;
7216 new_r10=0;
7217 new_r21=0;
7218 new_r22=0;
7219 IkReal gconst3=((3.14159265358979)+(((-1.0)*x578)));
7220 IkReal gconst4=x577;
7221 IkReal gconst5=((1.0)*new_r01);
7222 j3eval[0]=1.0;
7223 j3eval[1]=1.0;
7224 j3eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r01*new_r01))))))+(IKabs(((1.0)*new_r01*new_r11))));
7225 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
7226 {
7227 {
7228 IkReal j3eval[4];
7229 IkReal x580=((-1.0)*new_r11);
7230 CheckValue<IkReal> x582 = IKatan2WithCheck(IkReal(x580),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7231 if(!x582.valid){
7232 continue;
7233 }
7234 IkReal x581=((1.0)*(x582.value));
7235 sj4=0;
7236 cj4=1.0;
7237 j4=0;
7238 sj5=gconst4;
7239 cj5=gconst5;
7240 j5=((3.14159265)+(((-1.0)*x581)));
7241 new_r00=0;
7242 new_r10=0;
7243 new_r21=0;
7244 new_r22=0;
7245 IkReal gconst3=((3.14159265358979)+(((-1.0)*x581)));
7246 IkReal gconst4=x580;
7247 IkReal gconst5=((1.0)*new_r01);
7248 j3eval[0]=-1.0;
7249 j3eval[1]=new_r01;
7250 j3eval[2]=1.0;
7251 j3eval[3]=-1.0;
7252 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 || IKabs(j3eval[3]) < 0.0000010000000000 )
7253 {
7254 {
7255 IkReal j3eval[3];
7256 IkReal x583=((-1.0)*new_r11);
7257 CheckValue<IkReal> x585 = IKatan2WithCheck(IkReal(x583),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7258 if(!x585.valid){
7259 continue;
7260 }
7261 IkReal x584=((1.0)*(x585.value));
7262 sj4=0;
7263 cj4=1.0;
7264 j4=0;
7265 sj5=gconst4;
7266 cj5=gconst5;
7267 j5=((3.14159265)+(((-1.0)*x584)));
7268 new_r00=0;
7269 new_r10=0;
7270 new_r21=0;
7271 new_r22=0;
7272 IkReal gconst3=((3.14159265358979)+(((-1.0)*x584)));
7273 IkReal gconst4=x583;
7274 IkReal gconst5=((1.0)*new_r01);
7275 j3eval[0]=-1.0;
7276 j3eval[1]=-1.0;
7277 j3eval[2]=((IKabs(((2.0)*new_r01*new_r11)))+(IKabs(((-1.0)+(((2.0)*(new_r01*new_r01)))))));
7278 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
7279 {
7280 continue; // 3 cases reached
7281 
7282 } else
7283 {
7284 {
7285 IkReal j3array[1], cj3array[1], sj3array[1];
7286 bool j3valid[1]={false};
7287 _nj3 = 1;
7288 IkReal x586=((1.0)*new_r01);
7289 CheckValue<IkReal> x587 = IKatan2WithCheck(IkReal(((new_r01*new_r01)+(((-1.0)*(gconst4*gconst4))))),IkReal(((((-1.0)*new_r11*x586))+((gconst4*gconst5)))),IKFAST_ATAN2_MAGTHRESH);
7290 if(!x587.valid){
7291 continue;
7292 }
7293 CheckValue<IkReal> x588=IKPowWithIntegerCheck(IKsign((((gconst4*new_r11))+(((-1.0)*gconst5*x586)))),-1);
7294 if(!x588.valid){
7295 continue;
7296 }
7297 j3array[0]=((-1.5707963267949)+(x587.value)+(((1.5707963267949)*(x588.value))));
7298 sj3array[0]=IKsin(j3array[0]);
7299 cj3array[0]=IKcos(j3array[0]);
7300 if( j3array[0] > IKPI )
7301 {
7302  j3array[0]-=IK2PI;
7303 }
7304 else if( j3array[0] < -IKPI )
7305 { j3array[0]+=IK2PI;
7306 }
7307 j3valid[0] = true;
7308 for(int ij3 = 0; ij3 < 1; ++ij3)
7309 {
7310 if( !j3valid[ij3] )
7311 {
7312  continue;
7313 }
7314 _ij3[0] = ij3; _ij3[1] = -1;
7315 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
7316 {
7317 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
7318 {
7319  j3valid[iij3]=false; _ij3[1] = iij3; break;
7320 }
7321 }
7322 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
7323 {
7324 IkReal evalcond[6];
7325 IkReal x589=IKsin(j3);
7326 IkReal x590=IKcos(j3);
7327 IkReal x591=(gconst4*x589);
7328 IkReal x592=(gconst4*x590);
7329 IkReal x593=((1.0)*x590);
7330 IkReal x594=(gconst5*x589);
7331 IkReal x595=(gconst5*x593);
7332 evalcond[0]=(gconst4+((new_r01*x590))+((new_r11*x589)));
7333 evalcond[1]=(x594+x592+new_r01);
7334 evalcond[2]=((((-1.0)*x595))+x591);
7335 evalcond[3]=((((-1.0)*new_r11*x593))+gconst5+((new_r01*x589)));
7336 evalcond[4]=((((-1.0)*x595))+x591+new_r11);
7337 evalcond[5]=((((-1.0)*x594))+(((-1.0)*x592)));
7338 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7339 {
7340 continue;
7341 }
7342 }
7343 
7344 {
7345 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7346 vinfos[0].jointtype = 1;
7347 vinfos[0].foffset = j0;
7348 vinfos[0].indices[0] = _ij0[0];
7349 vinfos[0].indices[1] = _ij0[1];
7350 vinfos[0].maxsolutions = _nj0;
7351 vinfos[1].jointtype = 1;
7352 vinfos[1].foffset = j1;
7353 vinfos[1].indices[0] = _ij1[0];
7354 vinfos[1].indices[1] = _ij1[1];
7355 vinfos[1].maxsolutions = _nj1;
7356 vinfos[2].jointtype = 1;
7357 vinfos[2].foffset = j2;
7358 vinfos[2].indices[0] = _ij2[0];
7359 vinfos[2].indices[1] = _ij2[1];
7360 vinfos[2].maxsolutions = _nj2;
7361 vinfos[3].jointtype = 1;
7362 vinfos[3].foffset = j3;
7363 vinfos[3].indices[0] = _ij3[0];
7364 vinfos[3].indices[1] = _ij3[1];
7365 vinfos[3].maxsolutions = _nj3;
7366 vinfos[4].jointtype = 1;
7367 vinfos[4].foffset = j4;
7368 vinfos[4].indices[0] = _ij4[0];
7369 vinfos[4].indices[1] = _ij4[1];
7370 vinfos[4].maxsolutions = _nj4;
7371 vinfos[5].jointtype = 1;
7372 vinfos[5].foffset = j5;
7373 vinfos[5].indices[0] = _ij5[0];
7374 vinfos[5].indices[1] = _ij5[1];
7375 vinfos[5].maxsolutions = _nj5;
7376 std::vector<int> vfree(0);
7377 solutions.AddSolution(vinfos,vfree);
7378 }
7379 }
7380 }
7381 
7382 }
7383 
7384 }
7385 
7386 } else
7387 {
7388 {
7389 IkReal j3array[1], cj3array[1], sj3array[1];
7390 bool j3valid[1]={false};
7391 _nj3 = 1;
7392 CheckValue<IkReal> x596=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst4*gconst4)))+(((-1.0)*(gconst5*gconst5))))),-1);
7393 if(!x596.valid){
7394 continue;
7395 }
7396 CheckValue<IkReal> x597 = IKatan2WithCheck(IkReal((gconst5*new_r01)),IkReal((gconst4*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7397 if(!x597.valid){
7398 continue;
7399 }
7400 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x596.value)))+(x597.value));
7401 sj3array[0]=IKsin(j3array[0]);
7402 cj3array[0]=IKcos(j3array[0]);
7403 if( j3array[0] > IKPI )
7404 {
7405  j3array[0]-=IK2PI;
7406 }
7407 else if( j3array[0] < -IKPI )
7408 { j3array[0]+=IK2PI;
7409 }
7410 j3valid[0] = true;
7411 for(int ij3 = 0; ij3 < 1; ++ij3)
7412 {
7413 if( !j3valid[ij3] )
7414 {
7415  continue;
7416 }
7417 _ij3[0] = ij3; _ij3[1] = -1;
7418 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
7419 {
7420 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
7421 {
7422  j3valid[iij3]=false; _ij3[1] = iij3; break;
7423 }
7424 }
7425 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
7426 {
7427 IkReal evalcond[6];
7428 IkReal x598=IKsin(j3);
7429 IkReal x599=IKcos(j3);
7430 IkReal x600=(gconst4*x598);
7431 IkReal x601=(gconst4*x599);
7432 IkReal x602=((1.0)*x599);
7433 IkReal x603=(gconst5*x598);
7434 IkReal x604=(gconst5*x602);
7435 evalcond[0]=(((new_r11*x598))+gconst4+((new_r01*x599)));
7436 evalcond[1]=(x603+x601+new_r01);
7437 evalcond[2]=(x600+(((-1.0)*x604)));
7438 evalcond[3]=((((-1.0)*new_r11*x602))+gconst5+((new_r01*x598)));
7439 evalcond[4]=(x600+(((-1.0)*x604))+new_r11);
7440 evalcond[5]=((((-1.0)*x601))+(((-1.0)*x603)));
7441 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7442 {
7443 continue;
7444 }
7445 }
7446 
7447 {
7448 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7449 vinfos[0].jointtype = 1;
7450 vinfos[0].foffset = j0;
7451 vinfos[0].indices[0] = _ij0[0];
7452 vinfos[0].indices[1] = _ij0[1];
7453 vinfos[0].maxsolutions = _nj0;
7454 vinfos[1].jointtype = 1;
7455 vinfos[1].foffset = j1;
7456 vinfos[1].indices[0] = _ij1[0];
7457 vinfos[1].indices[1] = _ij1[1];
7458 vinfos[1].maxsolutions = _nj1;
7459 vinfos[2].jointtype = 1;
7460 vinfos[2].foffset = j2;
7461 vinfos[2].indices[0] = _ij2[0];
7462 vinfos[2].indices[1] = _ij2[1];
7463 vinfos[2].maxsolutions = _nj2;
7464 vinfos[3].jointtype = 1;
7465 vinfos[3].foffset = j3;
7466 vinfos[3].indices[0] = _ij3[0];
7467 vinfos[3].indices[1] = _ij3[1];
7468 vinfos[3].maxsolutions = _nj3;
7469 vinfos[4].jointtype = 1;
7470 vinfos[4].foffset = j4;
7471 vinfos[4].indices[0] = _ij4[0];
7472 vinfos[4].indices[1] = _ij4[1];
7473 vinfos[4].maxsolutions = _nj4;
7474 vinfos[5].jointtype = 1;
7475 vinfos[5].foffset = j5;
7476 vinfos[5].indices[0] = _ij5[0];
7477 vinfos[5].indices[1] = _ij5[1];
7478 vinfos[5].maxsolutions = _nj5;
7479 std::vector<int> vfree(0);
7480 solutions.AddSolution(vinfos,vfree);
7481 }
7482 }
7483 }
7484 
7485 }
7486 
7487 }
7488 
7489 } else
7490 {
7491 {
7492 IkReal j3array[1], cj3array[1], sj3array[1];
7493 bool j3valid[1]={false};
7494 _nj3 = 1;
7495 CheckValue<IkReal> x605=IKPowWithIntegerCheck(IKsign((((gconst5*new_r01))+(((-1.0)*gconst4*new_r11)))),-1);
7496 if(!x605.valid){
7497 continue;
7498 }
7499 CheckValue<IkReal> x606 = IKatan2WithCheck(IkReal(gconst4*gconst4),IkReal(((-1.0)*gconst4*gconst5)),IKFAST_ATAN2_MAGTHRESH);
7500 if(!x606.valid){
7501 continue;
7502 }
7503 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x605.value)))+(x606.value));
7504 sj3array[0]=IKsin(j3array[0]);
7505 cj3array[0]=IKcos(j3array[0]);
7506 if( j3array[0] > IKPI )
7507 {
7508  j3array[0]-=IK2PI;
7509 }
7510 else if( j3array[0] < -IKPI )
7511 { j3array[0]+=IK2PI;
7512 }
7513 j3valid[0] = true;
7514 for(int ij3 = 0; ij3 < 1; ++ij3)
7515 {
7516 if( !j3valid[ij3] )
7517 {
7518  continue;
7519 }
7520 _ij3[0] = ij3; _ij3[1] = -1;
7521 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
7522 {
7523 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
7524 {
7525  j3valid[iij3]=false; _ij3[1] = iij3; break;
7526 }
7527 }
7528 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
7529 {
7530 IkReal evalcond[6];
7531 IkReal x607=IKsin(j3);
7532 IkReal x608=IKcos(j3);
7533 IkReal x609=(gconst4*x607);
7534 IkReal x610=(gconst4*x608);
7535 IkReal x611=((1.0)*x608);
7536 IkReal x612=(gconst5*x607);
7537 IkReal x613=(gconst5*x611);
7538 evalcond[0]=(gconst4+((new_r11*x607))+((new_r01*x608)));
7539 evalcond[1]=(x610+x612+new_r01);
7540 evalcond[2]=((((-1.0)*x613))+x609);
7541 evalcond[3]=(gconst5+(((-1.0)*new_r11*x611))+((new_r01*x607)));
7542 evalcond[4]=((((-1.0)*x613))+x609+new_r11);
7543 evalcond[5]=((((-1.0)*x610))+(((-1.0)*x612)));
7544 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7545 {
7546 continue;
7547 }
7548 }
7549 
7550 {
7551 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7552 vinfos[0].jointtype = 1;
7553 vinfos[0].foffset = j0;
7554 vinfos[0].indices[0] = _ij0[0];
7555 vinfos[0].indices[1] = _ij0[1];
7556 vinfos[0].maxsolutions = _nj0;
7557 vinfos[1].jointtype = 1;
7558 vinfos[1].foffset = j1;
7559 vinfos[1].indices[0] = _ij1[0];
7560 vinfos[1].indices[1] = _ij1[1];
7561 vinfos[1].maxsolutions = _nj1;
7562 vinfos[2].jointtype = 1;
7563 vinfos[2].foffset = j2;
7564 vinfos[2].indices[0] = _ij2[0];
7565 vinfos[2].indices[1] = _ij2[1];
7566 vinfos[2].maxsolutions = _nj2;
7567 vinfos[3].jointtype = 1;
7568 vinfos[3].foffset = j3;
7569 vinfos[3].indices[0] = _ij3[0];
7570 vinfos[3].indices[1] = _ij3[1];
7571 vinfos[3].maxsolutions = _nj3;
7572 vinfos[4].jointtype = 1;
7573 vinfos[4].foffset = j4;
7574 vinfos[4].indices[0] = _ij4[0];
7575 vinfos[4].indices[1] = _ij4[1];
7576 vinfos[4].maxsolutions = _nj4;
7577 vinfos[5].jointtype = 1;
7578 vinfos[5].foffset = j5;
7579 vinfos[5].indices[0] = _ij5[0];
7580 vinfos[5].indices[1] = _ij5[1];
7581 vinfos[5].maxsolutions = _nj5;
7582 std::vector<int> vfree(0);
7583 solutions.AddSolution(vinfos,vfree);
7584 }
7585 }
7586 }
7587 
7588 }
7589 
7590 }
7591 
7592 }
7593 } while(0);
7594 if( bgotonextstatement )
7595 {
7596 bool bgotonextstatement = true;
7597 do
7598 {
7599 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
7600 if( IKabs(evalcond[0]) < 0.0000050000000000 )
7601 {
7602 bgotonextstatement=false;
7603 {
7604 IkReal j3eval[1];
7605 IkReal x614=((-1.0)*new_r11);
7606 CheckValue<IkReal> x616 = IKatan2WithCheck(IkReal(x614),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
7607 if(!x616.valid){
7608 continue;
7609 }
7610 IkReal x615=((1.0)*(x616.value));
7611 sj4=0;
7612 cj4=1.0;
7613 j4=0;
7614 sj5=gconst4;
7615 cj5=gconst5;
7616 j5=((3.14159265)+(((-1.0)*x615)));
7617 new_r01=0;
7618 new_r10=0;
7619 IkReal gconst3=((3.14159265358979)+(((-1.0)*x615)));
7620 IkReal x617 = new_r11*new_r11;
7621 if(IKabs(x617)==0){
7622 continue;
7623 }
7624 IkReal gconst4=(x614*(pow(x617,-0.5)));
7625 IkReal gconst5=0;
7626 j3eval[0]=new_r00;
7627 if( IKabs(j3eval[0]) < 0.0000010000000000 )
7628 {
7629 {
7630 IkReal j3eval[1];
7631 IkReal x618=((-1.0)*new_r11);
7632 CheckValue<IkReal> x620 = IKatan2WithCheck(IkReal(x618),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
7633 if(!x620.valid){
7634 continue;
7635 }
7636 IkReal x619=((1.0)*(x620.value));
7637 sj4=0;
7638 cj4=1.0;
7639 j4=0;
7640 sj5=gconst4;
7641 cj5=gconst5;
7642 j5=((3.14159265)+(((-1.0)*x619)));
7643 new_r01=0;
7644 new_r10=0;
7645 IkReal gconst3=((3.14159265358979)+(((-1.0)*x619)));
7646 IkReal x621 = new_r11*new_r11;
7647 if(IKabs(x621)==0){
7648 continue;
7649 }
7650 IkReal gconst4=(x618*(pow(x621,-0.5)));
7651 IkReal gconst5=0;
7652 j3eval[0]=new_r11;
7653 if( IKabs(j3eval[0]) < 0.0000010000000000 )
7654 {
7655 {
7656 IkReal j3array[2], cj3array[2], sj3array[2];
7657 bool j3valid[2]={false};
7658 _nj3 = 2;
7659 CheckValue<IkReal> x622=IKPowWithIntegerCheck(gconst4,-1);
7660 if(!x622.valid){
7661 continue;
7662 }
7663 sj3array[0]=((-1.0)*new_r00*(x622.value));
7664 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
7665 {
7666  j3valid[0] = j3valid[1] = true;
7667  j3array[0] = IKasin(sj3array[0]);
7668  cj3array[0] = IKcos(j3array[0]);
7669  sj3array[1] = sj3array[0];
7670  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
7671  cj3array[1] = -cj3array[0];
7672 }
7673 else if( isnan(sj3array[0]) )
7674 {
7675  // probably any value will work
7676  j3valid[0] = true;
7677  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
7678 }
7679 for(int ij3 = 0; ij3 < 2; ++ij3)
7680 {
7681 if( !j3valid[ij3] )
7682 {
7683  continue;
7684 }
7685 _ij3[0] = ij3; _ij3[1] = -1;
7686 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
7687 {
7688 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
7689 {
7690  j3valid[iij3]=false; _ij3[1] = iij3; break;
7691 }
7692 }
7693 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
7694 {
7695 IkReal evalcond[6];
7696 IkReal x623=IKcos(j3);
7697 IkReal x624=IKsin(j3);
7698 evalcond[0]=(gconst4*x623);
7699 evalcond[1]=(new_r00*x623);
7700 evalcond[2]=((-1.0)*new_r11*x623);
7701 evalcond[3]=(gconst4+((new_r00*x624)));
7702 evalcond[4]=(gconst4+((new_r11*x624)));
7703 evalcond[5]=(((gconst4*x624))+new_r11);
7704 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7705 {
7706 continue;
7707 }
7708 }
7709 
7710 {
7711 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7712 vinfos[0].jointtype = 1;
7713 vinfos[0].foffset = j0;
7714 vinfos[0].indices[0] = _ij0[0];
7715 vinfos[0].indices[1] = _ij0[1];
7716 vinfos[0].maxsolutions = _nj0;
7717 vinfos[1].jointtype = 1;
7718 vinfos[1].foffset = j1;
7719 vinfos[1].indices[0] = _ij1[0];
7720 vinfos[1].indices[1] = _ij1[1];
7721 vinfos[1].maxsolutions = _nj1;
7722 vinfos[2].jointtype = 1;
7723 vinfos[2].foffset = j2;
7724 vinfos[2].indices[0] = _ij2[0];
7725 vinfos[2].indices[1] = _ij2[1];
7726 vinfos[2].maxsolutions = _nj2;
7727 vinfos[3].jointtype = 1;
7728 vinfos[3].foffset = j3;
7729 vinfos[3].indices[0] = _ij3[0];
7730 vinfos[3].indices[1] = _ij3[1];
7731 vinfos[3].maxsolutions = _nj3;
7732 vinfos[4].jointtype = 1;
7733 vinfos[4].foffset = j4;
7734 vinfos[4].indices[0] = _ij4[0];
7735 vinfos[4].indices[1] = _ij4[1];
7736 vinfos[4].maxsolutions = _nj4;
7737 vinfos[5].jointtype = 1;
7738 vinfos[5].foffset = j5;
7739 vinfos[5].indices[0] = _ij5[0];
7740 vinfos[5].indices[1] = _ij5[1];
7741 vinfos[5].maxsolutions = _nj5;
7742 std::vector<int> vfree(0);
7743 solutions.AddSolution(vinfos,vfree);
7744 }
7745 }
7746 }
7747 
7748 } else
7749 {
7750 {
7751 IkReal j3array[2], cj3array[2], sj3array[2];
7752 bool j3valid[2]={false};
7753 _nj3 = 2;
7754 CheckValue<IkReal> x625=IKPowWithIntegerCheck(new_r11,-1);
7755 if(!x625.valid){
7756 continue;
7757 }
7758 sj3array[0]=((-1.0)*gconst4*(x625.value));
7759 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
7760 {
7761  j3valid[0] = j3valid[1] = true;
7762  j3array[0] = IKasin(sj3array[0]);
7763  cj3array[0] = IKcos(j3array[0]);
7764  sj3array[1] = sj3array[0];
7765  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
7766  cj3array[1] = -cj3array[0];
7767 }
7768 else if( isnan(sj3array[0]) )
7769 {
7770  // probably any value will work
7771  j3valid[0] = true;
7772  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
7773 }
7774 for(int ij3 = 0; ij3 < 2; ++ij3)
7775 {
7776 if( !j3valid[ij3] )
7777 {
7778  continue;
7779 }
7780 _ij3[0] = ij3; _ij3[1] = -1;
7781 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
7782 {
7783 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
7784 {
7785  j3valid[iij3]=false; _ij3[1] = iij3; break;
7786 }
7787 }
7788 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
7789 {
7790 IkReal evalcond[6];
7791 IkReal x626=IKcos(j3);
7792 IkReal x627=IKsin(j3);
7793 IkReal x628=(gconst4*x627);
7794 evalcond[0]=(gconst4*x626);
7795 evalcond[1]=(new_r00*x626);
7796 evalcond[2]=((-1.0)*new_r11*x626);
7797 evalcond[3]=(gconst4+((new_r00*x627)));
7798 evalcond[4]=(x628+new_r00);
7799 evalcond[5]=(x628+new_r11);
7800 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7801 {
7802 continue;
7803 }
7804 }
7805 
7806 {
7807 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7808 vinfos[0].jointtype = 1;
7809 vinfos[0].foffset = j0;
7810 vinfos[0].indices[0] = _ij0[0];
7811 vinfos[0].indices[1] = _ij0[1];
7812 vinfos[0].maxsolutions = _nj0;
7813 vinfos[1].jointtype = 1;
7814 vinfos[1].foffset = j1;
7815 vinfos[1].indices[0] = _ij1[0];
7816 vinfos[1].indices[1] = _ij1[1];
7817 vinfos[1].maxsolutions = _nj1;
7818 vinfos[2].jointtype = 1;
7819 vinfos[2].foffset = j2;
7820 vinfos[2].indices[0] = _ij2[0];
7821 vinfos[2].indices[1] = _ij2[1];
7822 vinfos[2].maxsolutions = _nj2;
7823 vinfos[3].jointtype = 1;
7824 vinfos[3].foffset = j3;
7825 vinfos[3].indices[0] = _ij3[0];
7826 vinfos[3].indices[1] = _ij3[1];
7827 vinfos[3].maxsolutions = _nj3;
7828 vinfos[4].jointtype = 1;
7829 vinfos[4].foffset = j4;
7830 vinfos[4].indices[0] = _ij4[0];
7831 vinfos[4].indices[1] = _ij4[1];
7832 vinfos[4].maxsolutions = _nj4;
7833 vinfos[5].jointtype = 1;
7834 vinfos[5].foffset = j5;
7835 vinfos[5].indices[0] = _ij5[0];
7836 vinfos[5].indices[1] = _ij5[1];
7837 vinfos[5].maxsolutions = _nj5;
7838 std::vector<int> vfree(0);
7839 solutions.AddSolution(vinfos,vfree);
7840 }
7841 }
7842 }
7843 
7844 }
7845 
7846 }
7847 
7848 } else
7849 {
7850 {
7851 IkReal j3array[2], cj3array[2], sj3array[2];
7852 bool j3valid[2]={false};
7853 _nj3 = 2;
7854 CheckValue<IkReal> x629=IKPowWithIntegerCheck(new_r00,-1);
7855 if(!x629.valid){
7856 continue;
7857 }
7858 sj3array[0]=((-1.0)*gconst4*(x629.value));
7859 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
7860 {
7861  j3valid[0] = j3valid[1] = true;
7862  j3array[0] = IKasin(sj3array[0]);
7863  cj3array[0] = IKcos(j3array[0]);
7864  sj3array[1] = sj3array[0];
7865  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
7866  cj3array[1] = -cj3array[0];
7867 }
7868 else if( isnan(sj3array[0]) )
7869 {
7870  // probably any value will work
7871  j3valid[0] = true;
7872  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
7873 }
7874 for(int ij3 = 0; ij3 < 2; ++ij3)
7875 {
7876 if( !j3valid[ij3] )
7877 {
7878  continue;
7879 }
7880 _ij3[0] = ij3; _ij3[1] = -1;
7881 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
7882 {
7883 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
7884 {
7885  j3valid[iij3]=false; _ij3[1] = iij3; break;
7886 }
7887 }
7888 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
7889 {
7890 IkReal evalcond[6];
7891 IkReal x630=IKcos(j3);
7892 IkReal x631=IKsin(j3);
7893 IkReal x632=(gconst4*x631);
7894 evalcond[0]=(gconst4*x630);
7895 evalcond[1]=(new_r00*x630);
7896 evalcond[2]=((-1.0)*new_r11*x630);
7897 evalcond[3]=(gconst4+((new_r11*x631)));
7898 evalcond[4]=(x632+new_r00);
7899 evalcond[5]=(x632+new_r11);
7900 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7901 {
7902 continue;
7903 }
7904 }
7905 
7906 {
7907 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7908 vinfos[0].jointtype = 1;
7909 vinfos[0].foffset = j0;
7910 vinfos[0].indices[0] = _ij0[0];
7911 vinfos[0].indices[1] = _ij0[1];
7912 vinfos[0].maxsolutions = _nj0;
7913 vinfos[1].jointtype = 1;
7914 vinfos[1].foffset = j1;
7915 vinfos[1].indices[0] = _ij1[0];
7916 vinfos[1].indices[1] = _ij1[1];
7917 vinfos[1].maxsolutions = _nj1;
7918 vinfos[2].jointtype = 1;
7919 vinfos[2].foffset = j2;
7920 vinfos[2].indices[0] = _ij2[0];
7921 vinfos[2].indices[1] = _ij2[1];
7922 vinfos[2].maxsolutions = _nj2;
7923 vinfos[3].jointtype = 1;
7924 vinfos[3].foffset = j3;
7925 vinfos[3].indices[0] = _ij3[0];
7926 vinfos[3].indices[1] = _ij3[1];
7927 vinfos[3].maxsolutions = _nj3;
7928 vinfos[4].jointtype = 1;
7929 vinfos[4].foffset = j4;
7930 vinfos[4].indices[0] = _ij4[0];
7931 vinfos[4].indices[1] = _ij4[1];
7932 vinfos[4].maxsolutions = _nj4;
7933 vinfos[5].jointtype = 1;
7934 vinfos[5].foffset = j5;
7935 vinfos[5].indices[0] = _ij5[0];
7936 vinfos[5].indices[1] = _ij5[1];
7937 vinfos[5].maxsolutions = _nj5;
7938 std::vector<int> vfree(0);
7939 solutions.AddSolution(vinfos,vfree);
7940 }
7941 }
7942 }
7943 
7944 }
7945 
7946 }
7947 
7948 }
7949 } while(0);
7950 if( bgotonextstatement )
7951 {
7952 bool bgotonextstatement = true;
7953 do
7954 {
7955 evalcond[0]=IKabs(new_r11);
7956 if( IKabs(evalcond[0]) < 0.0000050000000000 )
7957 {
7958 bgotonextstatement=false;
7959 {
7960 IkReal j3eval[1];
7961 CheckValue<IkReal> x634 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7962 if(!x634.valid){
7963 continue;
7964 }
7965 IkReal x633=((1.0)*(x634.value));
7966 sj4=0;
7967 cj4=1.0;
7968 j4=0;
7969 sj5=gconst4;
7970 cj5=gconst5;
7971 j5=((3.14159265)+(((-1.0)*x633)));
7972 new_r11=0;
7973 IkReal gconst3=((3.14159265358979)+(((-1.0)*x633)));
7974 IkReal gconst4=0;
7975 IkReal x635 = new_r01*new_r01;
7976 if(IKabs(x635)==0){
7977 continue;
7978 }
7979 IkReal gconst5=((1.0)*new_r01*(pow(x635,-0.5)));
7980 j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
7981 if( IKabs(j3eval[0]) < 0.0000010000000000 )
7982 {
7983 {
7984 IkReal j3eval[1];
7985 CheckValue<IkReal> x637 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
7986 if(!x637.valid){
7987 continue;
7988 }
7989 IkReal x636=((1.0)*(x637.value));
7990 sj4=0;
7991 cj4=1.0;
7992 j4=0;
7993 sj5=gconst4;
7994 cj5=gconst5;
7995 j5=((3.14159265)+(((-1.0)*x636)));
7996 new_r11=0;
7997 IkReal gconst3=((3.14159265358979)+(((-1.0)*x636)));
7998 IkReal gconst4=0;
7999 IkReal x638 = new_r01*new_r01;
8000 if(IKabs(x638)==0){
8001 continue;
8002 }
8003 IkReal gconst5=((1.0)*new_r01*(pow(x638,-0.5)));
8004 j3eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
8005 if( IKabs(j3eval[0]) < 0.0000010000000000 )
8006 {
8007 {
8008 IkReal j3eval[1];
8009 CheckValue<IkReal> x640 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
8010 if(!x640.valid){
8011 continue;
8012 }
8013 IkReal x639=((1.0)*(x640.value));
8014 sj4=0;
8015 cj4=1.0;
8016 j4=0;
8017 sj5=gconst4;
8018 cj5=gconst5;
8019 j5=((3.14159265)+(((-1.0)*x639)));
8020 new_r11=0;
8021 IkReal gconst3=((3.14159265358979)+(((-1.0)*x639)));
8022 IkReal gconst4=0;
8023 IkReal x641 = new_r01*new_r01;
8024 if(IKabs(x641)==0){
8025 continue;
8026 }
8027 IkReal gconst5=((1.0)*new_r01*(pow(x641,-0.5)));
8028 j3eval[0]=new_r01;
8029 if( IKabs(j3eval[0]) < 0.0000010000000000 )
8030 {
8031 continue; // 3 cases reached
8032 
8033 } else
8034 {
8035 {
8036 IkReal j3array[1], cj3array[1], sj3array[1];
8037 bool j3valid[1]={false};
8038 _nj3 = 1;
8039 CheckValue<IkReal> x642=IKPowWithIntegerCheck(new_r01,-1);
8040 if(!x642.valid){
8041 continue;
8042 }
8043 CheckValue<IkReal> x643=IKPowWithIntegerCheck(gconst5,-1);
8044 if(!x643.valid){
8045 continue;
8046 }
8047 if( IKabs(((-1.0)*gconst5*(x642.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r00*(x643.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst5*(x642.value)))+IKsqr((new_r00*(x643.value)))-1) <= IKFAST_SINCOS_THRESH )
8048  continue;
8049 j3array[0]=IKatan2(((-1.0)*gconst5*(x642.value)), (new_r00*(x643.value)));
8050 sj3array[0]=IKsin(j3array[0]);
8051 cj3array[0]=IKcos(j3array[0]);
8052 if( j3array[0] > IKPI )
8053 {
8054  j3array[0]-=IK2PI;
8055 }
8056 else if( j3array[0] < -IKPI )
8057 { j3array[0]+=IK2PI;
8058 }
8059 j3valid[0] = true;
8060 for(int ij3 = 0; ij3 < 1; ++ij3)
8061 {
8062 if( !j3valid[ij3] )
8063 {
8064  continue;
8065 }
8066 _ij3[0] = ij3; _ij3[1] = -1;
8067 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8068 {
8069 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8070 {
8071  j3valid[iij3]=false; _ij3[1] = iij3; break;
8072 }
8073 }
8074 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8075 {
8076 IkReal evalcond[8];
8077 IkReal x644=IKcos(j3);
8078 IkReal x645=IKsin(j3);
8079 IkReal x646=((1.0)*gconst5);
8080 evalcond[0]=(new_r01*x644);
8081 evalcond[1]=((-1.0)*gconst5*x644);
8082 evalcond[2]=(gconst5+((new_r01*x645)));
8083 evalcond[3]=(new_r01+((gconst5*x645)));
8084 evalcond[4]=((((-1.0)*x644*x646))+new_r00);
8085 evalcond[5]=((((-1.0)*x645*x646))+new_r10);
8086 evalcond[6]=((((-1.0)*new_r10*x644))+((new_r00*x645)));
8087 evalcond[7]=((((-1.0)*x646))+((new_r10*x645))+((new_r00*x644)));
8088 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8089 {
8090 continue;
8091 }
8092 }
8093 
8094 {
8095 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8096 vinfos[0].jointtype = 1;
8097 vinfos[0].foffset = j0;
8098 vinfos[0].indices[0] = _ij0[0];
8099 vinfos[0].indices[1] = _ij0[1];
8100 vinfos[0].maxsolutions = _nj0;
8101 vinfos[1].jointtype = 1;
8102 vinfos[1].foffset = j1;
8103 vinfos[1].indices[0] = _ij1[0];
8104 vinfos[1].indices[1] = _ij1[1];
8105 vinfos[1].maxsolutions = _nj1;
8106 vinfos[2].jointtype = 1;
8107 vinfos[2].foffset = j2;
8108 vinfos[2].indices[0] = _ij2[0];
8109 vinfos[2].indices[1] = _ij2[1];
8110 vinfos[2].maxsolutions = _nj2;
8111 vinfos[3].jointtype = 1;
8112 vinfos[3].foffset = j3;
8113 vinfos[3].indices[0] = _ij3[0];
8114 vinfos[3].indices[1] = _ij3[1];
8115 vinfos[3].maxsolutions = _nj3;
8116 vinfos[4].jointtype = 1;
8117 vinfos[4].foffset = j4;
8118 vinfos[4].indices[0] = _ij4[0];
8119 vinfos[4].indices[1] = _ij4[1];
8120 vinfos[4].maxsolutions = _nj4;
8121 vinfos[5].jointtype = 1;
8122 vinfos[5].foffset = j5;
8123 vinfos[5].indices[0] = _ij5[0];
8124 vinfos[5].indices[1] = _ij5[1];
8125 vinfos[5].maxsolutions = _nj5;
8126 std::vector<int> vfree(0);
8127 solutions.AddSolution(vinfos,vfree);
8128 }
8129 }
8130 }
8131 
8132 }
8133 
8134 }
8135 
8136 } else
8137 {
8138 {
8139 IkReal j3array[1], cj3array[1], sj3array[1];
8140 bool j3valid[1]={false};
8141 _nj3 = 1;
8142 CheckValue<IkReal> x647 = IKatan2WithCheck(IkReal(((-1.0)*new_r01)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
8143 if(!x647.valid){
8144 continue;
8145 }
8147 if(!x648.valid){
8148 continue;
8149 }
8150 j3array[0]=((-1.5707963267949)+(x647.value)+(((1.5707963267949)*(x648.value))));
8151 sj3array[0]=IKsin(j3array[0]);
8152 cj3array[0]=IKcos(j3array[0]);
8153 if( j3array[0] > IKPI )
8154 {
8155  j3array[0]-=IK2PI;
8156 }
8157 else if( j3array[0] < -IKPI )
8158 { j3array[0]+=IK2PI;
8159 }
8160 j3valid[0] = true;
8161 for(int ij3 = 0; ij3 < 1; ++ij3)
8162 {
8163 if( !j3valid[ij3] )
8164 {
8165  continue;
8166 }
8167 _ij3[0] = ij3; _ij3[1] = -1;
8168 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8169 {
8170 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8171 {
8172  j3valid[iij3]=false; _ij3[1] = iij3; break;
8173 }
8174 }
8175 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8176 {
8177 IkReal evalcond[8];
8178 IkReal x649=IKcos(j3);
8179 IkReal x650=IKsin(j3);
8180 IkReal x651=((1.0)*gconst5);
8181 evalcond[0]=(new_r01*x649);
8182 evalcond[1]=((-1.0)*gconst5*x649);
8183 evalcond[2]=(gconst5+((new_r01*x650)));
8184 evalcond[3]=(new_r01+((gconst5*x650)));
8185 evalcond[4]=((((-1.0)*x649*x651))+new_r00);
8186 evalcond[5]=((((-1.0)*x650*x651))+new_r10);
8187 evalcond[6]=((((-1.0)*new_r10*x649))+((new_r00*x650)));
8188 evalcond[7]=((((-1.0)*x651))+((new_r00*x649))+((new_r10*x650)));
8189 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8190 {
8191 continue;
8192 }
8193 }
8194 
8195 {
8196 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8197 vinfos[0].jointtype = 1;
8198 vinfos[0].foffset = j0;
8199 vinfos[0].indices[0] = _ij0[0];
8200 vinfos[0].indices[1] = _ij0[1];
8201 vinfos[0].maxsolutions = _nj0;
8202 vinfos[1].jointtype = 1;
8203 vinfos[1].foffset = j1;
8204 vinfos[1].indices[0] = _ij1[0];
8205 vinfos[1].indices[1] = _ij1[1];
8206 vinfos[1].maxsolutions = _nj1;
8207 vinfos[2].jointtype = 1;
8208 vinfos[2].foffset = j2;
8209 vinfos[2].indices[0] = _ij2[0];
8210 vinfos[2].indices[1] = _ij2[1];
8211 vinfos[2].maxsolutions = _nj2;
8212 vinfos[3].jointtype = 1;
8213 vinfos[3].foffset = j3;
8214 vinfos[3].indices[0] = _ij3[0];
8215 vinfos[3].indices[1] = _ij3[1];
8216 vinfos[3].maxsolutions = _nj3;
8217 vinfos[4].jointtype = 1;
8218 vinfos[4].foffset = j4;
8219 vinfos[4].indices[0] = _ij4[0];
8220 vinfos[4].indices[1] = _ij4[1];
8221 vinfos[4].maxsolutions = _nj4;
8222 vinfos[5].jointtype = 1;
8223 vinfos[5].foffset = j5;
8224 vinfos[5].indices[0] = _ij5[0];
8225 vinfos[5].indices[1] = _ij5[1];
8226 vinfos[5].maxsolutions = _nj5;
8227 std::vector<int> vfree(0);
8228 solutions.AddSolution(vinfos,vfree);
8229 }
8230 }
8231 }
8232 
8233 }
8234 
8235 }
8236 
8237 } else
8238 {
8239 {
8240 IkReal j3array[1], cj3array[1], sj3array[1];
8241 bool j3valid[1]={false};
8242 _nj3 = 1;
8243 CheckValue<IkReal> x652 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
8244 if(!x652.valid){
8245 continue;
8246 }
8248 if(!x653.valid){
8249 continue;
8250 }
8251 j3array[0]=((-1.5707963267949)+(x652.value)+(((1.5707963267949)*(x653.value))));
8252 sj3array[0]=IKsin(j3array[0]);
8253 cj3array[0]=IKcos(j3array[0]);
8254 if( j3array[0] > IKPI )
8255 {
8256  j3array[0]-=IK2PI;
8257 }
8258 else if( j3array[0] < -IKPI )
8259 { j3array[0]+=IK2PI;
8260 }
8261 j3valid[0] = true;
8262 for(int ij3 = 0; ij3 < 1; ++ij3)
8263 {
8264 if( !j3valid[ij3] )
8265 {
8266  continue;
8267 }
8268 _ij3[0] = ij3; _ij3[1] = -1;
8269 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8270 {
8271 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8272 {
8273  j3valid[iij3]=false; _ij3[1] = iij3; break;
8274 }
8275 }
8276 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8277 {
8278 IkReal evalcond[8];
8279 IkReal x654=IKcos(j3);
8280 IkReal x655=IKsin(j3);
8281 IkReal x656=((1.0)*gconst5);
8282 evalcond[0]=(new_r01*x654);
8283 evalcond[1]=((-1.0)*gconst5*x654);
8284 evalcond[2]=(gconst5+((new_r01*x655)));
8285 evalcond[3]=(new_r01+((gconst5*x655)));
8286 evalcond[4]=(new_r00+(((-1.0)*x654*x656)));
8287 evalcond[5]=((((-1.0)*x655*x656))+new_r10);
8288 evalcond[6]=((((-1.0)*new_r10*x654))+((new_r00*x655)));
8289 evalcond[7]=((((-1.0)*x656))+((new_r10*x655))+((new_r00*x654)));
8290 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8291 {
8292 continue;
8293 }
8294 }
8295 
8296 {
8297 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8298 vinfos[0].jointtype = 1;
8299 vinfos[0].foffset = j0;
8300 vinfos[0].indices[0] = _ij0[0];
8301 vinfos[0].indices[1] = _ij0[1];
8302 vinfos[0].maxsolutions = _nj0;
8303 vinfos[1].jointtype = 1;
8304 vinfos[1].foffset = j1;
8305 vinfos[1].indices[0] = _ij1[0];
8306 vinfos[1].indices[1] = _ij1[1];
8307 vinfos[1].maxsolutions = _nj1;
8308 vinfos[2].jointtype = 1;
8309 vinfos[2].foffset = j2;
8310 vinfos[2].indices[0] = _ij2[0];
8311 vinfos[2].indices[1] = _ij2[1];
8312 vinfos[2].maxsolutions = _nj2;
8313 vinfos[3].jointtype = 1;
8314 vinfos[3].foffset = j3;
8315 vinfos[3].indices[0] = _ij3[0];
8316 vinfos[3].indices[1] = _ij3[1];
8317 vinfos[3].maxsolutions = _nj3;
8318 vinfos[4].jointtype = 1;
8319 vinfos[4].foffset = j4;
8320 vinfos[4].indices[0] = _ij4[0];
8321 vinfos[4].indices[1] = _ij4[1];
8322 vinfos[4].maxsolutions = _nj4;
8323 vinfos[5].jointtype = 1;
8324 vinfos[5].foffset = j5;
8325 vinfos[5].indices[0] = _ij5[0];
8326 vinfos[5].indices[1] = _ij5[1];
8327 vinfos[5].maxsolutions = _nj5;
8328 std::vector<int> vfree(0);
8329 solutions.AddSolution(vinfos,vfree);
8330 }
8331 }
8332 }
8333 
8334 }
8335 
8336 }
8337 
8338 }
8339 } while(0);
8340 if( bgotonextstatement )
8341 {
8342 bool bgotonextstatement = true;
8343 do
8344 {
8345 if( 1 )
8346 {
8347 bgotonextstatement=false;
8348 continue; // branch miss [j3]
8349 
8350 }
8351 } while(0);
8352 if( bgotonextstatement )
8353 {
8354 }
8355 }
8356 }
8357 }
8358 }
8359 }
8360 
8361 } else
8362 {
8363 {
8364 IkReal j3array[1], cj3array[1], sj3array[1];
8365 bool j3valid[1]={false};
8366 _nj3 = 1;
8367 IkReal x657=((1.0)*new_r01);
8368 CheckValue<IkReal> x658 = IKatan2WithCheck(IkReal(((new_r01*new_r01)+(((-1.0)*(gconst4*gconst4))))),IkReal(((((-1.0)*new_r11*x657))+((gconst4*gconst5)))),IKFAST_ATAN2_MAGTHRESH);
8369 if(!x658.valid){
8370 continue;
8371 }
8372 CheckValue<IkReal> x659=IKPowWithIntegerCheck(IKsign((((gconst4*new_r11))+(((-1.0)*gconst5*x657)))),-1);
8373 if(!x659.valid){
8374 continue;
8375 }
8376 j3array[0]=((-1.5707963267949)+(x658.value)+(((1.5707963267949)*(x659.value))));
8377 sj3array[0]=IKsin(j3array[0]);
8378 cj3array[0]=IKcos(j3array[0]);
8379 if( j3array[0] > IKPI )
8380 {
8381  j3array[0]-=IK2PI;
8382 }
8383 else if( j3array[0] < -IKPI )
8384 { j3array[0]+=IK2PI;
8385 }
8386 j3valid[0] = true;
8387 for(int ij3 = 0; ij3 < 1; ++ij3)
8388 {
8389 if( !j3valid[ij3] )
8390 {
8391  continue;
8392 }
8393 _ij3[0] = ij3; _ij3[1] = -1;
8394 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8395 {
8396 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8397 {
8398  j3valid[iij3]=false; _ij3[1] = iij3; break;
8399 }
8400 }
8401 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8402 {
8403 IkReal evalcond[8];
8404 IkReal x660=IKsin(j3);
8405 IkReal x661=IKcos(j3);
8406 IkReal x662=((1.0)*gconst5);
8407 IkReal x663=(gconst4*x660);
8408 IkReal x664=(gconst4*x661);
8409 IkReal x665=((1.0)*x661);
8410 IkReal x666=(x661*x662);
8411 evalcond[0]=(gconst4+((new_r11*x660))+((new_r01*x661)));
8412 evalcond[1]=(((gconst5*x660))+x664+new_r01);
8413 evalcond[2]=(gconst4+(((-1.0)*new_r10*x665))+((new_r00*x660)));
8414 evalcond[3]=(gconst5+(((-1.0)*new_r11*x665))+((new_r01*x660)));
8415 evalcond[4]=((((-1.0)*x666))+x663+new_r00);
8416 evalcond[5]=((((-1.0)*x666))+x663+new_r11);
8417 evalcond[6]=(((new_r10*x660))+(((-1.0)*x662))+((new_r00*x661)));
8418 evalcond[7]=((((-1.0)*x660*x662))+(((-1.0)*x664))+new_r10);
8419 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8420 {
8421 continue;
8422 }
8423 }
8424 
8425 {
8426 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8427 vinfos[0].jointtype = 1;
8428 vinfos[0].foffset = j0;
8429 vinfos[0].indices[0] = _ij0[0];
8430 vinfos[0].indices[1] = _ij0[1];
8431 vinfos[0].maxsolutions = _nj0;
8432 vinfos[1].jointtype = 1;
8433 vinfos[1].foffset = j1;
8434 vinfos[1].indices[0] = _ij1[0];
8435 vinfos[1].indices[1] = _ij1[1];
8436 vinfos[1].maxsolutions = _nj1;
8437 vinfos[2].jointtype = 1;
8438 vinfos[2].foffset = j2;
8439 vinfos[2].indices[0] = _ij2[0];
8440 vinfos[2].indices[1] = _ij2[1];
8441 vinfos[2].maxsolutions = _nj2;
8442 vinfos[3].jointtype = 1;
8443 vinfos[3].foffset = j3;
8444 vinfos[3].indices[0] = _ij3[0];
8445 vinfos[3].indices[1] = _ij3[1];
8446 vinfos[3].maxsolutions = _nj3;
8447 vinfos[4].jointtype = 1;
8448 vinfos[4].foffset = j4;
8449 vinfos[4].indices[0] = _ij4[0];
8450 vinfos[4].indices[1] = _ij4[1];
8451 vinfos[4].maxsolutions = _nj4;
8452 vinfos[5].jointtype = 1;
8453 vinfos[5].foffset = j5;
8454 vinfos[5].indices[0] = _ij5[0];
8455 vinfos[5].indices[1] = _ij5[1];
8456 vinfos[5].maxsolutions = _nj5;
8457 std::vector<int> vfree(0);
8458 solutions.AddSolution(vinfos,vfree);
8459 }
8460 }
8461 }
8462 
8463 }
8464 
8465 }
8466 
8467 } else
8468 {
8469 {
8470 IkReal j3array[1], cj3array[1], sj3array[1];
8471 bool j3valid[1]={false};
8472 _nj3 = 1;
8473 IkReal x667=((1.0)*gconst4);
8474 CheckValue<IkReal> x668 = IKatan2WithCheck(IkReal(((gconst4*gconst4)+((new_r01*new_r10)))),IkReal((((new_r00*new_r01))+(((-1.0)*gconst5*x667)))),IKFAST_ATAN2_MAGTHRESH);
8475 if(!x668.valid){
8476 continue;
8477 }
8478 CheckValue<IkReal> x669=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst5*new_r10))+(((-1.0)*new_r00*x667)))),-1);
8479 if(!x669.valid){
8480 continue;
8481 }
8482 j3array[0]=((-1.5707963267949)+(x668.value)+(((1.5707963267949)*(x669.value))));
8483 sj3array[0]=IKsin(j3array[0]);
8484 cj3array[0]=IKcos(j3array[0]);
8485 if( j3array[0] > IKPI )
8486 {
8487  j3array[0]-=IK2PI;
8488 }
8489 else if( j3array[0] < -IKPI )
8490 { j3array[0]+=IK2PI;
8491 }
8492 j3valid[0] = true;
8493 for(int ij3 = 0; ij3 < 1; ++ij3)
8494 {
8495 if( !j3valid[ij3] )
8496 {
8497  continue;
8498 }
8499 _ij3[0] = ij3; _ij3[1] = -1;
8500 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8501 {
8502 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8503 {
8504  j3valid[iij3]=false; _ij3[1] = iij3; break;
8505 }
8506 }
8507 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8508 {
8509 IkReal evalcond[8];
8510 IkReal x670=IKsin(j3);
8511 IkReal x671=IKcos(j3);
8512 IkReal x672=((1.0)*gconst5);
8513 IkReal x673=(gconst4*x670);
8514 IkReal x674=(gconst4*x671);
8515 IkReal x675=((1.0)*x671);
8516 IkReal x676=(x671*x672);
8517 evalcond[0]=(((new_r11*x670))+((new_r01*x671))+gconst4);
8518 evalcond[1]=(((gconst5*x670))+x674+new_r01);
8519 evalcond[2]=(((new_r00*x670))+gconst4+(((-1.0)*new_r10*x675)));
8520 evalcond[3]=(((new_r01*x670))+gconst5+(((-1.0)*new_r11*x675)));
8521 evalcond[4]=(x673+new_r00+(((-1.0)*x676)));
8522 evalcond[5]=(x673+new_r11+(((-1.0)*x676)));
8523 evalcond[6]=(((new_r00*x671))+((new_r10*x670))+(((-1.0)*x672)));
8524 evalcond[7]=((((-1.0)*x670*x672))+(((-1.0)*x674))+new_r10);
8525 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8526 {
8527 continue;
8528 }
8529 }
8530 
8531 {
8532 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8533 vinfos[0].jointtype = 1;
8534 vinfos[0].foffset = j0;
8535 vinfos[0].indices[0] = _ij0[0];
8536 vinfos[0].indices[1] = _ij0[1];
8537 vinfos[0].maxsolutions = _nj0;
8538 vinfos[1].jointtype = 1;
8539 vinfos[1].foffset = j1;
8540 vinfos[1].indices[0] = _ij1[0];
8541 vinfos[1].indices[1] = _ij1[1];
8542 vinfos[1].maxsolutions = _nj1;
8543 vinfos[2].jointtype = 1;
8544 vinfos[2].foffset = j2;
8545 vinfos[2].indices[0] = _ij2[0];
8546 vinfos[2].indices[1] = _ij2[1];
8547 vinfos[2].maxsolutions = _nj2;
8548 vinfos[3].jointtype = 1;
8549 vinfos[3].foffset = j3;
8550 vinfos[3].indices[0] = _ij3[0];
8551 vinfos[3].indices[1] = _ij3[1];
8552 vinfos[3].maxsolutions = _nj3;
8553 vinfos[4].jointtype = 1;
8554 vinfos[4].foffset = j4;
8555 vinfos[4].indices[0] = _ij4[0];
8556 vinfos[4].indices[1] = _ij4[1];
8557 vinfos[4].maxsolutions = _nj4;
8558 vinfos[5].jointtype = 1;
8559 vinfos[5].foffset = j5;
8560 vinfos[5].indices[0] = _ij5[0];
8561 vinfos[5].indices[1] = _ij5[1];
8562 vinfos[5].maxsolutions = _nj5;
8563 std::vector<int> vfree(0);
8564 solutions.AddSolution(vinfos,vfree);
8565 }
8566 }
8567 }
8568 
8569 }
8570 
8571 }
8572 
8573 } else
8574 {
8575 {
8576 IkReal j3array[1], cj3array[1], sj3array[1];
8577 bool j3valid[1]={false};
8578 _nj3 = 1;
8579 IkReal x677=((1.0)*new_r11);
8580 CheckValue<IkReal> x678=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*new_r01))+(((-1.0)*new_r10*x677)))),-1);
8581 if(!x678.valid){
8582 continue;
8583 }
8584 CheckValue<IkReal> x679 = IKatan2WithCheck(IkReal((((gconst4*new_r10))+((gconst4*new_r01)))),IkReal((((gconst4*new_r00))+(((-1.0)*gconst4*x677)))),IKFAST_ATAN2_MAGTHRESH);
8585 if(!x679.valid){
8586 continue;
8587 }
8588 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x678.value)))+(x679.value));
8589 sj3array[0]=IKsin(j3array[0]);
8590 cj3array[0]=IKcos(j3array[0]);
8591 if( j3array[0] > IKPI )
8592 {
8593  j3array[0]-=IK2PI;
8594 }
8595 else if( j3array[0] < -IKPI )
8596 { j3array[0]+=IK2PI;
8597 }
8598 j3valid[0] = true;
8599 for(int ij3 = 0; ij3 < 1; ++ij3)
8600 {
8601 if( !j3valid[ij3] )
8602 {
8603  continue;
8604 }
8605 _ij3[0] = ij3; _ij3[1] = -1;
8606 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8607 {
8608 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8609 {
8610  j3valid[iij3]=false; _ij3[1] = iij3; break;
8611 }
8612 }
8613 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8614 {
8615 IkReal evalcond[8];
8616 IkReal x680=IKsin(j3);
8617 IkReal x681=IKcos(j3);
8618 IkReal x682=((1.0)*gconst5);
8619 IkReal x683=(gconst4*x680);
8620 IkReal x684=(gconst4*x681);
8621 IkReal x685=((1.0)*x681);
8622 IkReal x686=(x681*x682);
8623 evalcond[0]=(gconst4+((new_r01*x681))+((new_r11*x680)));
8624 evalcond[1]=(((gconst5*x680))+x684+new_r01);
8625 evalcond[2]=((((-1.0)*new_r10*x685))+gconst4+((new_r00*x680)));
8626 evalcond[3]=(gconst5+((new_r01*x680))+(((-1.0)*new_r11*x685)));
8627 evalcond[4]=((((-1.0)*x686))+x683+new_r00);
8628 evalcond[5]=((((-1.0)*x686))+x683+new_r11);
8629 evalcond[6]=((((-1.0)*x682))+((new_r00*x681))+((new_r10*x680)));
8630 evalcond[7]=((((-1.0)*x680*x682))+new_r10+(((-1.0)*x684)));
8631 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8632 {
8633 continue;
8634 }
8635 }
8636 
8637 {
8638 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8639 vinfos[0].jointtype = 1;
8640 vinfos[0].foffset = j0;
8641 vinfos[0].indices[0] = _ij0[0];
8642 vinfos[0].indices[1] = _ij0[1];
8643 vinfos[0].maxsolutions = _nj0;
8644 vinfos[1].jointtype = 1;
8645 vinfos[1].foffset = j1;
8646 vinfos[1].indices[0] = _ij1[0];
8647 vinfos[1].indices[1] = _ij1[1];
8648 vinfos[1].maxsolutions = _nj1;
8649 vinfos[2].jointtype = 1;
8650 vinfos[2].foffset = j2;
8651 vinfos[2].indices[0] = _ij2[0];
8652 vinfos[2].indices[1] = _ij2[1];
8653 vinfos[2].maxsolutions = _nj2;
8654 vinfos[3].jointtype = 1;
8655 vinfos[3].foffset = j3;
8656 vinfos[3].indices[0] = _ij3[0];
8657 vinfos[3].indices[1] = _ij3[1];
8658 vinfos[3].maxsolutions = _nj3;
8659 vinfos[4].jointtype = 1;
8660 vinfos[4].foffset = j4;
8661 vinfos[4].indices[0] = _ij4[0];
8662 vinfos[4].indices[1] = _ij4[1];
8663 vinfos[4].maxsolutions = _nj4;
8664 vinfos[5].jointtype = 1;
8665 vinfos[5].foffset = j5;
8666 vinfos[5].indices[0] = _ij5[0];
8667 vinfos[5].indices[1] = _ij5[1];
8668 vinfos[5].maxsolutions = _nj5;
8669 std::vector<int> vfree(0);
8670 solutions.AddSolution(vinfos,vfree);
8671 }
8672 }
8673 }
8674 
8675 }
8676 
8677 }
8678 
8679 }
8680 } while(0);
8681 if( bgotonextstatement )
8682 {
8683 bool bgotonextstatement = true;
8684 do
8685 {
8686 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j5))), 6.28318530717959)));
8687 if( IKabs(evalcond[0]) < 0.0000050000000000 )
8688 {
8689 bgotonextstatement=false;
8690 {
8691 IkReal j3array[1], cj3array[1], sj3array[1];
8692 bool j3valid[1]={false};
8693 _nj3 = 1;
8694 if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(new_r00)-1) <= IKFAST_SINCOS_THRESH )
8695  continue;
8696 j3array[0]=IKatan2(((-1.0)*new_r01), new_r00);
8697 sj3array[0]=IKsin(j3array[0]);
8698 cj3array[0]=IKcos(j3array[0]);
8699 if( j3array[0] > IKPI )
8700 {
8701  j3array[0]-=IK2PI;
8702 }
8703 else if( j3array[0] < -IKPI )
8704 { j3array[0]+=IK2PI;
8705 }
8706 j3valid[0] = true;
8707 for(int ij3 = 0; ij3 < 1; ++ij3)
8708 {
8709 if( !j3valid[ij3] )
8710 {
8711  continue;
8712 }
8713 _ij3[0] = ij3; _ij3[1] = -1;
8714 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8715 {
8716 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8717 {
8718  j3valid[iij3]=false; _ij3[1] = iij3; break;
8719 }
8720 }
8721 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8722 {
8723 IkReal evalcond[8];
8724 IkReal x687=IKsin(j3);
8725 IkReal x688=IKcos(j3);
8726 IkReal x689=((1.0)*x688);
8727 evalcond[0]=(x687+new_r01);
8728 evalcond[1]=((((-1.0)*x689))+new_r00);
8729 evalcond[2]=((((-1.0)*x689))+new_r11);
8730 evalcond[3]=(new_r10+(((-1.0)*x687)));
8731 evalcond[4]=(((new_r01*x688))+((new_r11*x687)));
8732 evalcond[5]=((((-1.0)*new_r10*x689))+((new_r00*x687)));
8733 evalcond[6]=((-1.0)+((new_r00*x688))+((new_r10*x687)));
8734 evalcond[7]=((1.0)+((new_r01*x687))+(((-1.0)*new_r11*x689)));
8735 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8736 {
8737 continue;
8738 }
8739 }
8740 
8741 {
8742 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8743 vinfos[0].jointtype = 1;
8744 vinfos[0].foffset = j0;
8745 vinfos[0].indices[0] = _ij0[0];
8746 vinfos[0].indices[1] = _ij0[1];
8747 vinfos[0].maxsolutions = _nj0;
8748 vinfos[1].jointtype = 1;
8749 vinfos[1].foffset = j1;
8750 vinfos[1].indices[0] = _ij1[0];
8751 vinfos[1].indices[1] = _ij1[1];
8752 vinfos[1].maxsolutions = _nj1;
8753 vinfos[2].jointtype = 1;
8754 vinfos[2].foffset = j2;
8755 vinfos[2].indices[0] = _ij2[0];
8756 vinfos[2].indices[1] = _ij2[1];
8757 vinfos[2].maxsolutions = _nj2;
8758 vinfos[3].jointtype = 1;
8759 vinfos[3].foffset = j3;
8760 vinfos[3].indices[0] = _ij3[0];
8761 vinfos[3].indices[1] = _ij3[1];
8762 vinfos[3].maxsolutions = _nj3;
8763 vinfos[4].jointtype = 1;
8764 vinfos[4].foffset = j4;
8765 vinfos[4].indices[0] = _ij4[0];
8766 vinfos[4].indices[1] = _ij4[1];
8767 vinfos[4].maxsolutions = _nj4;
8768 vinfos[5].jointtype = 1;
8769 vinfos[5].foffset = j5;
8770 vinfos[5].indices[0] = _ij5[0];
8771 vinfos[5].indices[1] = _ij5[1];
8772 vinfos[5].maxsolutions = _nj5;
8773 std::vector<int> vfree(0);
8774 solutions.AddSolution(vinfos,vfree);
8775 }
8776 }
8777 }
8778 
8779 }
8780 } while(0);
8781 if( bgotonextstatement )
8782 {
8783 bool bgotonextstatement = true;
8784 do
8785 {
8786 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j5)))), 6.28318530717959)));
8787 if( IKabs(evalcond[0]) < 0.0000050000000000 )
8788 {
8789 bgotonextstatement=false;
8790 {
8791 IkReal j3array[1], cj3array[1], sj3array[1];
8792 bool j3valid[1]={false};
8793 _nj3 = 1;
8794 if( IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r10))+IKsqr(((-1.0)*new_r00))-1) <= IKFAST_SINCOS_THRESH )
8795  continue;
8796 j3array[0]=IKatan2(((-1.0)*new_r10), ((-1.0)*new_r00));
8797 sj3array[0]=IKsin(j3array[0]);
8798 cj3array[0]=IKcos(j3array[0]);
8799 if( j3array[0] > IKPI )
8800 {
8801  j3array[0]-=IK2PI;
8802 }
8803 else if( j3array[0] < -IKPI )
8804 { j3array[0]+=IK2PI;
8805 }
8806 j3valid[0] = true;
8807 for(int ij3 = 0; ij3 < 1; ++ij3)
8808 {
8809 if( !j3valid[ij3] )
8810 {
8811  continue;
8812 }
8813 _ij3[0] = ij3; _ij3[1] = -1;
8814 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8815 {
8816 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8817 {
8818  j3valid[iij3]=false; _ij3[1] = iij3; break;
8819 }
8820 }
8821 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8822 {
8823 IkReal evalcond[8];
8824 IkReal x690=IKcos(j3);
8825 IkReal x691=IKsin(j3);
8826 IkReal x692=((1.0)*x690);
8827 evalcond[0]=(x690+new_r00);
8828 evalcond[1]=(x690+new_r11);
8829 evalcond[2]=(x691+new_r10);
8830 evalcond[3]=(new_r01+(((-1.0)*x691)));
8831 evalcond[4]=(((new_r11*x691))+((new_r01*x690)));
8832 evalcond[5]=((((-1.0)*new_r10*x692))+((new_r00*x691)));
8833 evalcond[6]=((1.0)+((new_r10*x691))+((new_r00*x690)));
8834 evalcond[7]=((-1.0)+(((-1.0)*new_r11*x692))+((new_r01*x691)));
8835 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
8836 {
8837 continue;
8838 }
8839 }
8840 
8841 {
8842 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8843 vinfos[0].jointtype = 1;
8844 vinfos[0].foffset = j0;
8845 vinfos[0].indices[0] = _ij0[0];
8846 vinfos[0].indices[1] = _ij0[1];
8847 vinfos[0].maxsolutions = _nj0;
8848 vinfos[1].jointtype = 1;
8849 vinfos[1].foffset = j1;
8850 vinfos[1].indices[0] = _ij1[0];
8851 vinfos[1].indices[1] = _ij1[1];
8852 vinfos[1].maxsolutions = _nj1;
8853 vinfos[2].jointtype = 1;
8854 vinfos[2].foffset = j2;
8855 vinfos[2].indices[0] = _ij2[0];
8856 vinfos[2].indices[1] = _ij2[1];
8857 vinfos[2].maxsolutions = _nj2;
8858 vinfos[3].jointtype = 1;
8859 vinfos[3].foffset = j3;
8860 vinfos[3].indices[0] = _ij3[0];
8861 vinfos[3].indices[1] = _ij3[1];
8862 vinfos[3].maxsolutions = _nj3;
8863 vinfos[4].jointtype = 1;
8864 vinfos[4].foffset = j4;
8865 vinfos[4].indices[0] = _ij4[0];
8866 vinfos[4].indices[1] = _ij4[1];
8867 vinfos[4].maxsolutions = _nj4;
8868 vinfos[5].jointtype = 1;
8869 vinfos[5].foffset = j5;
8870 vinfos[5].indices[0] = _ij5[0];
8871 vinfos[5].indices[1] = _ij5[1];
8872 vinfos[5].maxsolutions = _nj5;
8873 std::vector<int> vfree(0);
8874 solutions.AddSolution(vinfos,vfree);
8875 }
8876 }
8877 }
8878 
8879 }
8880 } while(0);
8881 if( bgotonextstatement )
8882 {
8883 bool bgotonextstatement = true;
8884 do
8885 {
8886 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
8887 if( IKabs(evalcond[0]) < 0.0000050000000000 )
8888 {
8889 bgotonextstatement=false;
8890 {
8891 IkReal j3eval[3];
8892 sj4=0;
8893 cj4=1.0;
8894 j4=0;
8895 new_r11=0;
8896 new_r00=0;
8897 j3eval[0]=new_r01;
8898 j3eval[1]=IKsign(new_r01);
8899 j3eval[2]=((IKabs(cj5))+(IKabs(sj5)));
8900 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
8901 {
8902 {
8903 IkReal j3eval[2];
8904 sj4=0;
8905 cj4=1.0;
8906 j4=0;
8907 new_r11=0;
8908 new_r00=0;
8909 j3eval[0]=new_r01;
8910 j3eval[1]=new_r10;
8911 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
8912 {
8913 {
8914 IkReal j3eval[2];
8915 sj4=0;
8916 cj4=1.0;
8917 j4=0;
8918 new_r11=0;
8919 new_r00=0;
8920 j3eval[0]=new_r01;
8921 j3eval[1]=sj5;
8922 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
8923 {
8924 {
8925 IkReal evalcond[1];
8926 bool bgotonextstatement = true;
8927 do
8928 {
8929 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j5))), 6.28318530717959)));
8930 if( IKabs(evalcond[0]) < 0.0000050000000000 )
8931 {
8932 bgotonextstatement=false;
8933 {
8934 IkReal j3array[2], cj3array[2], sj3array[2];
8935 bool j3valid[2]={false};
8936 _nj3 = 2;
8937 sj3array[0]=new_r10;
8938 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
8939 {
8940  j3valid[0] = j3valid[1] = true;
8941  j3array[0] = IKasin(sj3array[0]);
8942  cj3array[0] = IKcos(j3array[0]);
8943  sj3array[1] = sj3array[0];
8944  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
8945  cj3array[1] = -cj3array[0];
8946 }
8947 else if( isnan(sj3array[0]) )
8948 {
8949  // probably any value will work
8950  j3valid[0] = true;
8951  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
8952 }
8953 for(int ij3 = 0; ij3 < 2; ++ij3)
8954 {
8955 if( !j3valid[ij3] )
8956 {
8957  continue;
8958 }
8959 _ij3[0] = ij3; _ij3[1] = -1;
8960 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
8961 {
8962 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8963 {
8964  j3valid[iij3]=false; _ij3[1] = iij3; break;
8965 }
8966 }
8967 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8968 {
8969 IkReal evalcond[6];
8970 IkReal x693=IKcos(j3);
8971 IkReal x694=IKsin(j3);
8972 IkReal x695=((-1.0)*x693);
8973 evalcond[0]=(new_r01*x693);
8974 evalcond[1]=(x694+new_r01);
8975 evalcond[2]=x695;
8976 evalcond[3]=(new_r10*x695);
8977 evalcond[4]=((1.0)+((new_r01*x694)));
8978 evalcond[5]=((-1.0)+((new_r10*x694)));
8979 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8980 {
8981 continue;
8982 }
8983 }
8984 
8985 {
8986 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8987 vinfos[0].jointtype = 1;
8988 vinfos[0].foffset = j0;
8989 vinfos[0].indices[0] = _ij0[0];
8990 vinfos[0].indices[1] = _ij0[1];
8991 vinfos[0].maxsolutions = _nj0;
8992 vinfos[1].jointtype = 1;
8993 vinfos[1].foffset = j1;
8994 vinfos[1].indices[0] = _ij1[0];
8995 vinfos[1].indices[1] = _ij1[1];
8996 vinfos[1].maxsolutions = _nj1;
8997 vinfos[2].jointtype = 1;
8998 vinfos[2].foffset = j2;
8999 vinfos[2].indices[0] = _ij2[0];
9000 vinfos[2].indices[1] = _ij2[1];
9001 vinfos[2].maxsolutions = _nj2;
9002 vinfos[3].jointtype = 1;
9003 vinfos[3].foffset = j3;
9004 vinfos[3].indices[0] = _ij3[0];
9005 vinfos[3].indices[1] = _ij3[1];
9006 vinfos[3].maxsolutions = _nj3;
9007 vinfos[4].jointtype = 1;
9008 vinfos[4].foffset = j4;
9009 vinfos[4].indices[0] = _ij4[0];
9010 vinfos[4].indices[1] = _ij4[1];
9011 vinfos[4].maxsolutions = _nj4;
9012 vinfos[5].jointtype = 1;
9013 vinfos[5].foffset = j5;
9014 vinfos[5].indices[0] = _ij5[0];
9015 vinfos[5].indices[1] = _ij5[1];
9016 vinfos[5].maxsolutions = _nj5;
9017 std::vector<int> vfree(0);
9018 solutions.AddSolution(vinfos,vfree);
9019 }
9020 }
9021 }
9022 
9023 }
9024 } while(0);
9025 if( bgotonextstatement )
9026 {
9027 bool bgotonextstatement = true;
9028 do
9029 {
9030 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j5)))), 6.28318530717959)));
9031 if( IKabs(evalcond[0]) < 0.0000050000000000 )
9032 {
9033 bgotonextstatement=false;
9034 {
9035 IkReal j3array[2], cj3array[2], sj3array[2];
9036 bool j3valid[2]={false};
9037 _nj3 = 2;
9038 sj3array[0]=new_r01;
9039 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
9040 {
9041  j3valid[0] = j3valid[1] = true;
9042  j3array[0] = IKasin(sj3array[0]);
9043  cj3array[0] = IKcos(j3array[0]);
9044  sj3array[1] = sj3array[0];
9045  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
9046  cj3array[1] = -cj3array[0];
9047 }
9048 else if( isnan(sj3array[0]) )
9049 {
9050  // probably any value will work
9051  j3valid[0] = true;
9052  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
9053 }
9054 for(int ij3 = 0; ij3 < 2; ++ij3)
9055 {
9056 if( !j3valid[ij3] )
9057 {
9058  continue;
9059 }
9060 _ij3[0] = ij3; _ij3[1] = -1;
9061 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
9062 {
9063 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9064 {
9065  j3valid[iij3]=false; _ij3[1] = iij3; break;
9066 }
9067 }
9068 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9069 {
9070 IkReal evalcond[6];
9071 IkReal x696=IKcos(j3);
9072 IkReal x697=IKsin(j3);
9073 evalcond[0]=x696;
9074 evalcond[1]=(new_r01*x696);
9075 evalcond[2]=(x697+new_r10);
9076 evalcond[3]=((-1.0)*new_r10*x696);
9077 evalcond[4]=((-1.0)+((new_r01*x697)));
9078 evalcond[5]=((1.0)+((new_r10*x697)));
9079 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
9080 {
9081 continue;
9082 }
9083 }
9084 
9085 {
9086 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9087 vinfos[0].jointtype = 1;
9088 vinfos[0].foffset = j0;
9089 vinfos[0].indices[0] = _ij0[0];
9090 vinfos[0].indices[1] = _ij0[1];
9091 vinfos[0].maxsolutions = _nj0;
9092 vinfos[1].jointtype = 1;
9093 vinfos[1].foffset = j1;
9094 vinfos[1].indices[0] = _ij1[0];
9095 vinfos[1].indices[1] = _ij1[1];
9096 vinfos[1].maxsolutions = _nj1;
9097 vinfos[2].jointtype = 1;
9098 vinfos[2].foffset = j2;
9099 vinfos[2].indices[0] = _ij2[0];
9100 vinfos[2].indices[1] = _ij2[1];
9101 vinfos[2].maxsolutions = _nj2;
9102 vinfos[3].jointtype = 1;
9103 vinfos[3].foffset = j3;
9104 vinfos[3].indices[0] = _ij3[0];
9105 vinfos[3].indices[1] = _ij3[1];
9106 vinfos[3].maxsolutions = _nj3;
9107 vinfos[4].jointtype = 1;
9108 vinfos[4].foffset = j4;
9109 vinfos[4].indices[0] = _ij4[0];
9110 vinfos[4].indices[1] = _ij4[1];
9111 vinfos[4].maxsolutions = _nj4;
9112 vinfos[5].jointtype = 1;
9113 vinfos[5].foffset = j5;
9114 vinfos[5].indices[0] = _ij5[0];
9115 vinfos[5].indices[1] = _ij5[1];
9116 vinfos[5].maxsolutions = _nj5;
9117 std::vector<int> vfree(0);
9118 solutions.AddSolution(vinfos,vfree);
9119 }
9120 }
9121 }
9122 
9123 }
9124 } while(0);
9125 if( bgotonextstatement )
9126 {
9127 bool bgotonextstatement = true;
9128 do
9129 {
9130 if( 1 )
9131 {
9132 bgotonextstatement=false;
9133 continue; // branch miss [j3]
9134 
9135 }
9136 } while(0);
9137 if( bgotonextstatement )
9138 {
9139 }
9140 }
9141 }
9142 }
9143 
9144 } else
9145 {
9146 {
9147 IkReal j3array[1], cj3array[1], sj3array[1];
9148 bool j3valid[1]={false};
9149 _nj3 = 1;
9150 CheckValue<IkReal> x699=IKPowWithIntegerCheck(new_r01,-1);
9151 if(!x699.valid){
9152 continue;
9153 }
9154 IkReal x698=x699.value;
9156 if(!x700.valid){
9157 continue;
9158 }
9160 if(!x701.valid){
9161 continue;
9162 }
9163 if( IKabs(((-1.0)*cj5*x698)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x698*(x700.value)*(((((-1.0)*(x701.value)))+(cj5*cj5))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*cj5*x698))+IKsqr((x698*(x700.value)*(((((-1.0)*(x701.value)))+(cj5*cj5)))))-1) <= IKFAST_SINCOS_THRESH )
9164  continue;
9165 j3array[0]=IKatan2(((-1.0)*cj5*x698), (x698*(x700.value)*(((((-1.0)*(x701.value)))+(cj5*cj5)))));
9166 sj3array[0]=IKsin(j3array[0]);
9167 cj3array[0]=IKcos(j3array[0]);
9168 if( j3array[0] > IKPI )
9169 {
9170  j3array[0]-=IK2PI;
9171 }
9172 else if( j3array[0] < -IKPI )
9173 { j3array[0]+=IK2PI;
9174 }
9175 j3valid[0] = true;
9176 for(int ij3 = 0; ij3 < 1; ++ij3)
9177 {
9178 if( !j3valid[ij3] )
9179 {
9180  continue;
9181 }
9182 _ij3[0] = ij3; _ij3[1] = -1;
9183 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
9184 {
9185 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9186 {
9187  j3valid[iij3]=false; _ij3[1] = iij3; break;
9188 }
9189 }
9190 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9191 {
9192 IkReal evalcond[7];
9193 IkReal x702=IKcos(j3);
9194 IkReal x703=IKsin(j3);
9195 IkReal x704=((1.0)*cj5);
9196 IkReal x705=(sj5*x702);
9197 evalcond[0]=(cj5+((new_r01*x703)));
9198 evalcond[1]=(sj5+((new_r01*x702)));
9199 evalcond[2]=(sj5+(((-1.0)*new_r10*x702)));
9200 evalcond[3]=((((-1.0)*x704))+((new_r10*x703)));
9201 evalcond[4]=(((cj5*x703))+x705+new_r01);
9202 evalcond[5]=((((-1.0)*x702*x704))+((sj5*x703)));
9203 evalcond[6]=((((-1.0)*x705))+(((-1.0)*x703*x704))+new_r10);
9204 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9205 {
9206 continue;
9207 }
9208 }
9209 
9210 {
9211 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9212 vinfos[0].jointtype = 1;
9213 vinfos[0].foffset = j0;
9214 vinfos[0].indices[0] = _ij0[0];
9215 vinfos[0].indices[1] = _ij0[1];
9216 vinfos[0].maxsolutions = _nj0;
9217 vinfos[1].jointtype = 1;
9218 vinfos[1].foffset = j1;
9219 vinfos[1].indices[0] = _ij1[0];
9220 vinfos[1].indices[1] = _ij1[1];
9221 vinfos[1].maxsolutions = _nj1;
9222 vinfos[2].jointtype = 1;
9223 vinfos[2].foffset = j2;
9224 vinfos[2].indices[0] = _ij2[0];
9225 vinfos[2].indices[1] = _ij2[1];
9226 vinfos[2].maxsolutions = _nj2;
9227 vinfos[3].jointtype = 1;
9228 vinfos[3].foffset = j3;
9229 vinfos[3].indices[0] = _ij3[0];
9230 vinfos[3].indices[1] = _ij3[1];
9231 vinfos[3].maxsolutions = _nj3;
9232 vinfos[4].jointtype = 1;
9233 vinfos[4].foffset = j4;
9234 vinfos[4].indices[0] = _ij4[0];
9235 vinfos[4].indices[1] = _ij4[1];
9236 vinfos[4].maxsolutions = _nj4;
9237 vinfos[5].jointtype = 1;
9238 vinfos[5].foffset = j5;
9239 vinfos[5].indices[0] = _ij5[0];
9240 vinfos[5].indices[1] = _ij5[1];
9241 vinfos[5].maxsolutions = _nj5;
9242 std::vector<int> vfree(0);
9243 solutions.AddSolution(vinfos,vfree);
9244 }
9245 }
9246 }
9247 
9248 }
9249 
9250 }
9251 
9252 } else
9253 {
9254 {
9255 IkReal j3array[1], cj3array[1], sj3array[1];
9256 bool j3valid[1]={false};
9257 _nj3 = 1;
9258 CheckValue<IkReal> x706=IKPowWithIntegerCheck(new_r01,-1);
9259 if(!x706.valid){
9260 continue;
9261 }
9262 CheckValue<IkReal> x707=IKPowWithIntegerCheck(new_r10,-1);
9263 if(!x707.valid){
9264 continue;
9265 }
9266 if( IKabs(((-1.0)*cj5*(x706.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((sj5*(x707.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*cj5*(x706.value)))+IKsqr((sj5*(x707.value)))-1) <= IKFAST_SINCOS_THRESH )
9267  continue;
9268 j3array[0]=IKatan2(((-1.0)*cj5*(x706.value)), (sj5*(x707.value)));
9269 sj3array[0]=IKsin(j3array[0]);
9270 cj3array[0]=IKcos(j3array[0]);
9271 if( j3array[0] > IKPI )
9272 {
9273  j3array[0]-=IK2PI;
9274 }
9275 else if( j3array[0] < -IKPI )
9276 { j3array[0]+=IK2PI;
9277 }
9278 j3valid[0] = true;
9279 for(int ij3 = 0; ij3 < 1; ++ij3)
9280 {
9281 if( !j3valid[ij3] )
9282 {
9283  continue;
9284 }
9285 _ij3[0] = ij3; _ij3[1] = -1;
9286 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
9287 {
9288 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9289 {
9290  j3valid[iij3]=false; _ij3[1] = iij3; break;
9291 }
9292 }
9293 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9294 {
9295 IkReal evalcond[7];
9296 IkReal x708=IKcos(j3);
9297 IkReal x709=IKsin(j3);
9298 IkReal x710=((1.0)*cj5);
9299 IkReal x711=(sj5*x708);
9300 evalcond[0]=(cj5+((new_r01*x709)));
9301 evalcond[1]=(sj5+((new_r01*x708)));
9302 evalcond[2]=(sj5+(((-1.0)*new_r10*x708)));
9303 evalcond[3]=((((-1.0)*x710))+((new_r10*x709)));
9304 evalcond[4]=(((cj5*x709))+x711+new_r01);
9305 evalcond[5]=(((sj5*x709))+(((-1.0)*x708*x710)));
9306 evalcond[6]=((((-1.0)*x709*x710))+(((-1.0)*x711))+new_r10);
9307 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9308 {
9309 continue;
9310 }
9311 }
9312 
9313 {
9314 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9315 vinfos[0].jointtype = 1;
9316 vinfos[0].foffset = j0;
9317 vinfos[0].indices[0] = _ij0[0];
9318 vinfos[0].indices[1] = _ij0[1];
9319 vinfos[0].maxsolutions = _nj0;
9320 vinfos[1].jointtype = 1;
9321 vinfos[1].foffset = j1;
9322 vinfos[1].indices[0] = _ij1[0];
9323 vinfos[1].indices[1] = _ij1[1];
9324 vinfos[1].maxsolutions = _nj1;
9325 vinfos[2].jointtype = 1;
9326 vinfos[2].foffset = j2;
9327 vinfos[2].indices[0] = _ij2[0];
9328 vinfos[2].indices[1] = _ij2[1];
9329 vinfos[2].maxsolutions = _nj2;
9330 vinfos[3].jointtype = 1;
9331 vinfos[3].foffset = j3;
9332 vinfos[3].indices[0] = _ij3[0];
9333 vinfos[3].indices[1] = _ij3[1];
9334 vinfos[3].maxsolutions = _nj3;
9335 vinfos[4].jointtype = 1;
9336 vinfos[4].foffset = j4;
9337 vinfos[4].indices[0] = _ij4[0];
9338 vinfos[4].indices[1] = _ij4[1];
9339 vinfos[4].maxsolutions = _nj4;
9340 vinfos[5].jointtype = 1;
9341 vinfos[5].foffset = j5;
9342 vinfos[5].indices[0] = _ij5[0];
9343 vinfos[5].indices[1] = _ij5[1];
9344 vinfos[5].maxsolutions = _nj5;
9345 std::vector<int> vfree(0);
9346 solutions.AddSolution(vinfos,vfree);
9347 }
9348 }
9349 }
9350 
9351 }
9352 
9353 }
9354 
9355 } else
9356 {
9357 {
9358 IkReal j3array[1], cj3array[1], sj3array[1];
9359 bool j3valid[1]={false};
9360 _nj3 = 1;
9362 if(!x712.valid){
9363 continue;
9364 }
9365 CheckValue<IkReal> x713 = IKatan2WithCheck(IkReal(((-1.0)*cj5)),IkReal(((-1.0)*sj5)),IKFAST_ATAN2_MAGTHRESH);
9366 if(!x713.valid){
9367 continue;
9368 }
9369 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x712.value)))+(x713.value));
9370 sj3array[0]=IKsin(j3array[0]);
9371 cj3array[0]=IKcos(j3array[0]);
9372 if( j3array[0] > IKPI )
9373 {
9374  j3array[0]-=IK2PI;
9375 }
9376 else if( j3array[0] < -IKPI )
9377 { j3array[0]+=IK2PI;
9378 }
9379 j3valid[0] = true;
9380 for(int ij3 = 0; ij3 < 1; ++ij3)
9381 {
9382 if( !j3valid[ij3] )
9383 {
9384  continue;
9385 }
9386 _ij3[0] = ij3; _ij3[1] = -1;
9387 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
9388 {
9389 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9390 {
9391  j3valid[iij3]=false; _ij3[1] = iij3; break;
9392 }
9393 }
9394 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9395 {
9396 IkReal evalcond[7];
9397 IkReal x714=IKcos(j3);
9398 IkReal x715=IKsin(j3);
9399 IkReal x716=((1.0)*cj5);
9400 IkReal x717=(sj5*x714);
9401 evalcond[0]=(cj5+((new_r01*x715)));
9402 evalcond[1]=(sj5+((new_r01*x714)));
9403 evalcond[2]=(sj5+(((-1.0)*new_r10*x714)));
9404 evalcond[3]=((((-1.0)*x716))+((new_r10*x715)));
9405 evalcond[4]=(((cj5*x715))+x717+new_r01);
9406 evalcond[5]=((((-1.0)*x714*x716))+((sj5*x715)));
9407 evalcond[6]=((((-1.0)*x717))+new_r10+(((-1.0)*x715*x716)));
9408 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9409 {
9410 continue;
9411 }
9412 }
9413 
9414 {
9415 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9416 vinfos[0].jointtype = 1;
9417 vinfos[0].foffset = j0;
9418 vinfos[0].indices[0] = _ij0[0];
9419 vinfos[0].indices[1] = _ij0[1];
9420 vinfos[0].maxsolutions = _nj0;
9421 vinfos[1].jointtype = 1;
9422 vinfos[1].foffset = j1;
9423 vinfos[1].indices[0] = _ij1[0];
9424 vinfos[1].indices[1] = _ij1[1];
9425 vinfos[1].maxsolutions = _nj1;
9426 vinfos[2].jointtype = 1;
9427 vinfos[2].foffset = j2;
9428 vinfos[2].indices[0] = _ij2[0];
9429 vinfos[2].indices[1] = _ij2[1];
9430 vinfos[2].maxsolutions = _nj2;
9431 vinfos[3].jointtype = 1;
9432 vinfos[3].foffset = j3;
9433 vinfos[3].indices[0] = _ij3[0];
9434 vinfos[3].indices[1] = _ij3[1];
9435 vinfos[3].maxsolutions = _nj3;
9436 vinfos[4].jointtype = 1;
9437 vinfos[4].foffset = j4;
9438 vinfos[4].indices[0] = _ij4[0];
9439 vinfos[4].indices[1] = _ij4[1];
9440 vinfos[4].maxsolutions = _nj4;
9441 vinfos[5].jointtype = 1;
9442 vinfos[5].foffset = j5;
9443 vinfos[5].indices[0] = _ij5[0];
9444 vinfos[5].indices[1] = _ij5[1];
9445 vinfos[5].maxsolutions = _nj5;
9446 std::vector<int> vfree(0);
9447 solutions.AddSolution(vinfos,vfree);
9448 }
9449 }
9450 }
9451 
9452 }
9453 
9454 }
9455 
9456 }
9457 } while(0);
9458 if( bgotonextstatement )
9459 {
9460 bool bgotonextstatement = true;
9461 do
9462 {
9463 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
9464 if( IKabs(evalcond[0]) < 0.0000050000000000 )
9465 {
9466 bgotonextstatement=false;
9467 {
9468 IkReal j3eval[1];
9469 sj4=0;
9470 cj4=1.0;
9471 j4=0;
9472 new_r11=0;
9473 new_r01=0;
9474 new_r22=0;
9475 new_r20=0;
9476 j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
9477 if( IKabs(j3eval[0]) < 0.0000010000000000 )
9478 {
9479 continue; // no branches [j3]
9480 
9481 } else
9482 {
9483 {
9484 IkReal j3array[2], cj3array[2], sj3array[2];
9485 bool j3valid[2]={false};
9486 _nj3 = 2;
9487 CheckValue<IkReal> x719 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
9488 if(!x719.valid){
9489 continue;
9490 }
9491 IkReal x718=x719.value;
9492 j3array[0]=((-1.0)*x718);
9493 sj3array[0]=IKsin(j3array[0]);
9494 cj3array[0]=IKcos(j3array[0]);
9495 j3array[1]=((3.14159265358979)+(((-1.0)*x718)));
9496 sj3array[1]=IKsin(j3array[1]);
9497 cj3array[1]=IKcos(j3array[1]);
9498 if( j3array[0] > IKPI )
9499 {
9500  j3array[0]-=IK2PI;
9501 }
9502 else if( j3array[0] < -IKPI )
9503 { j3array[0]+=IK2PI;
9504 }
9505 j3valid[0] = true;
9506 if( j3array[1] > IKPI )
9507 {
9508  j3array[1]-=IK2PI;
9509 }
9510 else if( j3array[1] < -IKPI )
9511 { j3array[1]+=IK2PI;
9512 }
9513 j3valid[1] = true;
9514 for(int ij3 = 0; ij3 < 2; ++ij3)
9515 {
9516 if( !j3valid[ij3] )
9517 {
9518  continue;
9519 }
9520 _ij3[0] = ij3; _ij3[1] = -1;
9521 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
9522 {
9523 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9524 {
9525  j3valid[iij3]=false; _ij3[1] = iij3; break;
9526 }
9527 }
9528 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9529 {
9530 IkReal evalcond[1];
9531 evalcond[0]=(((new_r00*(IKsin(j3))))+(((-1.0)*new_r10*(IKcos(j3)))));
9532 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
9533 {
9534 continue;
9535 }
9536 }
9537 
9538 {
9539 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9540 vinfos[0].jointtype = 1;
9541 vinfos[0].foffset = j0;
9542 vinfos[0].indices[0] = _ij0[0];
9543 vinfos[0].indices[1] = _ij0[1];
9544 vinfos[0].maxsolutions = _nj0;
9545 vinfos[1].jointtype = 1;
9546 vinfos[1].foffset = j1;
9547 vinfos[1].indices[0] = _ij1[0];
9548 vinfos[1].indices[1] = _ij1[1];
9549 vinfos[1].maxsolutions = _nj1;
9550 vinfos[2].jointtype = 1;
9551 vinfos[2].foffset = j2;
9552 vinfos[2].indices[0] = _ij2[0];
9553 vinfos[2].indices[1] = _ij2[1];
9554 vinfos[2].maxsolutions = _nj2;
9555 vinfos[3].jointtype = 1;
9556 vinfos[3].foffset = j3;
9557 vinfos[3].indices[0] = _ij3[0];
9558 vinfos[3].indices[1] = _ij3[1];
9559 vinfos[3].maxsolutions = _nj3;
9560 vinfos[4].jointtype = 1;
9561 vinfos[4].foffset = j4;
9562 vinfos[4].indices[0] = _ij4[0];
9563 vinfos[4].indices[1] = _ij4[1];
9564 vinfos[4].maxsolutions = _nj4;
9565 vinfos[5].jointtype = 1;
9566 vinfos[5].foffset = j5;
9567 vinfos[5].indices[0] = _ij5[0];
9568 vinfos[5].indices[1] = _ij5[1];
9569 vinfos[5].maxsolutions = _nj5;
9570 std::vector<int> vfree(0);
9571 solutions.AddSolution(vinfos,vfree);
9572 }
9573 }
9574 }
9575 
9576 }
9577 
9578 }
9579 
9580 }
9581 } while(0);
9582 if( bgotonextstatement )
9583 {
9584 bool bgotonextstatement = true;
9585 do
9586 {
9587 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
9588 if( IKabs(evalcond[0]) < 0.0000050000000000 )
9589 {
9590 bgotonextstatement=false;
9591 {
9592 IkReal j3eval[1];
9593 sj4=0;
9594 cj4=1.0;
9595 j4=0;
9596 new_r00=0;
9597 new_r10=0;
9598 new_r21=0;
9599 new_r22=0;
9600 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
9601 if( IKabs(j3eval[0]) < 0.0000010000000000 )
9602 {
9603 continue; // no branches [j3]
9604 
9605 } else
9606 {
9607 {
9608 IkReal j3array[2], cj3array[2], sj3array[2];
9609 bool j3valid[2]={false};
9610 _nj3 = 2;
9611 CheckValue<IkReal> x721 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
9612 if(!x721.valid){
9613 continue;
9614 }
9615 IkReal x720=x721.value;
9616 j3array[0]=((-1.0)*x720);
9617 sj3array[0]=IKsin(j3array[0]);
9618 cj3array[0]=IKcos(j3array[0]);
9619 j3array[1]=((3.14159265358979)+(((-1.0)*x720)));
9620 sj3array[1]=IKsin(j3array[1]);
9621 cj3array[1]=IKcos(j3array[1]);
9622 if( j3array[0] > IKPI )
9623 {
9624  j3array[0]-=IK2PI;
9625 }
9626 else if( j3array[0] < -IKPI )
9627 { j3array[0]+=IK2PI;
9628 }
9629 j3valid[0] = true;
9630 if( j3array[1] > IKPI )
9631 {
9632  j3array[1]-=IK2PI;
9633 }
9634 else if( j3array[1] < -IKPI )
9635 { j3array[1]+=IK2PI;
9636 }
9637 j3valid[1] = true;
9638 for(int ij3 = 0; ij3 < 2; ++ij3)
9639 {
9640 if( !j3valid[ij3] )
9641 {
9642  continue;
9643 }
9644 _ij3[0] = ij3; _ij3[1] = -1;
9645 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
9646 {
9647 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9648 {
9649  j3valid[iij3]=false; _ij3[1] = iij3; break;
9650 }
9651 }
9652 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9653 {
9654 IkReal evalcond[1];
9655 evalcond[0]=(((new_r01*(IKsin(j3))))+(((-1.0)*new_r11*(IKcos(j3)))));
9656 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
9657 {
9658 continue;
9659 }
9660 }
9661 
9662 {
9663 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9664 vinfos[0].jointtype = 1;
9665 vinfos[0].foffset = j0;
9666 vinfos[0].indices[0] = _ij0[0];
9667 vinfos[0].indices[1] = _ij0[1];
9668 vinfos[0].maxsolutions = _nj0;
9669 vinfos[1].jointtype = 1;
9670 vinfos[1].foffset = j1;
9671 vinfos[1].indices[0] = _ij1[0];
9672 vinfos[1].indices[1] = _ij1[1];
9673 vinfos[1].maxsolutions = _nj1;
9674 vinfos[2].jointtype = 1;
9675 vinfos[2].foffset = j2;
9676 vinfos[2].indices[0] = _ij2[0];
9677 vinfos[2].indices[1] = _ij2[1];
9678 vinfos[2].maxsolutions = _nj2;
9679 vinfos[3].jointtype = 1;
9680 vinfos[3].foffset = j3;
9681 vinfos[3].indices[0] = _ij3[0];
9682 vinfos[3].indices[1] = _ij3[1];
9683 vinfos[3].maxsolutions = _nj3;
9684 vinfos[4].jointtype = 1;
9685 vinfos[4].foffset = j4;
9686 vinfos[4].indices[0] = _ij4[0];
9687 vinfos[4].indices[1] = _ij4[1];
9688 vinfos[4].maxsolutions = _nj4;
9689 vinfos[5].jointtype = 1;
9690 vinfos[5].foffset = j5;
9691 vinfos[5].indices[0] = _ij5[0];
9692 vinfos[5].indices[1] = _ij5[1];
9693 vinfos[5].maxsolutions = _nj5;
9694 std::vector<int> vfree(0);
9695 solutions.AddSolution(vinfos,vfree);
9696 }
9697 }
9698 }
9699 
9700 }
9701 
9702 }
9703 
9704 }
9705 } while(0);
9706 if( bgotonextstatement )
9707 {
9708 bool bgotonextstatement = true;
9709 do
9710 {
9711 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
9712 if( IKabs(evalcond[0]) < 0.0000050000000000 )
9713 {
9714 bgotonextstatement=false;
9715 {
9716 IkReal j3eval[3];
9717 sj4=0;
9718 cj4=1.0;
9719 j4=0;
9720 new_r01=0;
9721 new_r10=0;
9722 j3eval[0]=new_r11;
9723 j3eval[1]=IKsign(new_r11);
9724 j3eval[2]=((IKabs(cj5))+(IKabs(sj5)));
9725 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
9726 {
9727 {
9728 IkReal j3eval[3];
9729 sj4=0;
9730 cj4=1.0;
9731 j4=0;
9732 new_r01=0;
9733 new_r10=0;
9734 j3eval[0]=new_r00;
9735 j3eval[1]=((IKabs(cj5))+(IKabs(sj5)));
9736 j3eval[2]=IKsign(new_r00);
9737 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
9738 {
9739 {
9740 IkReal j3eval[2];
9741 sj4=0;
9742 cj4=1.0;
9743 j4=0;
9744 new_r01=0;
9745 new_r10=0;
9746 j3eval[0]=new_r00;
9747 j3eval[1]=new_r11;
9748 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
9749 {
9750 continue; // no branches [j3]
9751 
9752 } else
9753 {
9754 {
9755 IkReal j3array[1], cj3array[1], sj3array[1];
9756 bool j3valid[1]={false};
9757 _nj3 = 1;
9758 CheckValue<IkReal> x722=IKPowWithIntegerCheck(new_r00,-1);
9759 if(!x722.valid){
9760 continue;
9761 }
9762 CheckValue<IkReal> x723=IKPowWithIntegerCheck(new_r11,-1);
9763 if(!x723.valid){
9764 continue;
9765 }
9766 if( IKabs(((-1.0)*sj5*(x722.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((cj5*(x723.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*sj5*(x722.value)))+IKsqr((cj5*(x723.value)))-1) <= IKFAST_SINCOS_THRESH )
9767  continue;
9768 j3array[0]=IKatan2(((-1.0)*sj5*(x722.value)), (cj5*(x723.value)));
9769 sj3array[0]=IKsin(j3array[0]);
9770 cj3array[0]=IKcos(j3array[0]);
9771 if( j3array[0] > IKPI )
9772 {
9773  j3array[0]-=IK2PI;
9774 }
9775 else if( j3array[0] < -IKPI )
9776 { j3array[0]+=IK2PI;
9777 }
9778 j3valid[0] = true;
9779 for(int ij3 = 0; ij3 < 1; ++ij3)
9780 {
9781 if( !j3valid[ij3] )
9782 {
9783  continue;
9784 }
9785 _ij3[0] = ij3; _ij3[1] = -1;
9786 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
9787 {
9788 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9789 {
9790  j3valid[iij3]=false; _ij3[1] = iij3; break;
9791 }
9792 }
9793 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9794 {
9795 IkReal evalcond[7];
9796 IkReal x724=IKsin(j3);
9797 IkReal x725=IKcos(j3);
9798 IkReal x726=(sj5*x724);
9799 IkReal x727=((1.0)*x725);
9800 IkReal x728=(cj5*x727);
9801 evalcond[0]=(sj5+((new_r00*x724)));
9802 evalcond[1]=(sj5+((new_r11*x724)));
9803 evalcond[2]=(cj5+(((-1.0)*new_r11*x727)));
9804 evalcond[3]=(((new_r00*x725))+(((-1.0)*cj5)));
9805 evalcond[4]=(((cj5*x724))+((sj5*x725)));
9806 evalcond[5]=((((-1.0)*x728))+x726+new_r00);
9807 evalcond[6]=((((-1.0)*x728))+x726+new_r11);
9808 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9809 {
9810 continue;
9811 }
9812 }
9813 
9814 {
9815 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9816 vinfos[0].jointtype = 1;
9817 vinfos[0].foffset = j0;
9818 vinfos[0].indices[0] = _ij0[0];
9819 vinfos[0].indices[1] = _ij0[1];
9820 vinfos[0].maxsolutions = _nj0;
9821 vinfos[1].jointtype = 1;
9822 vinfos[1].foffset = j1;
9823 vinfos[1].indices[0] = _ij1[0];
9824 vinfos[1].indices[1] = _ij1[1];
9825 vinfos[1].maxsolutions = _nj1;
9826 vinfos[2].jointtype = 1;
9827 vinfos[2].foffset = j2;
9828 vinfos[2].indices[0] = _ij2[0];
9829 vinfos[2].indices[1] = _ij2[1];
9830 vinfos[2].maxsolutions = _nj2;
9831 vinfos[3].jointtype = 1;
9832 vinfos[3].foffset = j3;
9833 vinfos[3].indices[0] = _ij3[0];
9834 vinfos[3].indices[1] = _ij3[1];
9835 vinfos[3].maxsolutions = _nj3;
9836 vinfos[4].jointtype = 1;
9837 vinfos[4].foffset = j4;
9838 vinfos[4].indices[0] = _ij4[0];
9839 vinfos[4].indices[1] = _ij4[1];
9840 vinfos[4].maxsolutions = _nj4;
9841 vinfos[5].jointtype = 1;
9842 vinfos[5].foffset = j5;
9843 vinfos[5].indices[0] = _ij5[0];
9844 vinfos[5].indices[1] = _ij5[1];
9845 vinfos[5].maxsolutions = _nj5;
9846 std::vector<int> vfree(0);
9847 solutions.AddSolution(vinfos,vfree);
9848 }
9849 }
9850 }
9851 
9852 }
9853 
9854 }
9855 
9856 } else
9857 {
9858 {
9859 IkReal j3array[1], cj3array[1], sj3array[1];
9860 bool j3valid[1]={false};
9861 _nj3 = 1;
9863 if(!x729.valid){
9864 continue;
9865 }
9866 CheckValue<IkReal> x730 = IKatan2WithCheck(IkReal(((-1.0)*sj5)),IkReal(cj5),IKFAST_ATAN2_MAGTHRESH);
9867 if(!x730.valid){
9868 continue;
9869 }
9870 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x729.value)))+(x730.value));
9871 sj3array[0]=IKsin(j3array[0]);
9872 cj3array[0]=IKcos(j3array[0]);
9873 if( j3array[0] > IKPI )
9874 {
9875  j3array[0]-=IK2PI;
9876 }
9877 else if( j3array[0] < -IKPI )
9878 { j3array[0]+=IK2PI;
9879 }
9880 j3valid[0] = true;
9881 for(int ij3 = 0; ij3 < 1; ++ij3)
9882 {
9883 if( !j3valid[ij3] )
9884 {
9885  continue;
9886 }
9887 _ij3[0] = ij3; _ij3[1] = -1;
9888 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
9889 {
9890 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9891 {
9892  j3valid[iij3]=false; _ij3[1] = iij3; break;
9893 }
9894 }
9895 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9896 {
9897 IkReal evalcond[7];
9898 IkReal x731=IKsin(j3);
9899 IkReal x732=IKcos(j3);
9900 IkReal x733=(sj5*x731);
9901 IkReal x734=((1.0)*x732);
9902 IkReal x735=(cj5*x734);
9903 evalcond[0]=(sj5+((new_r00*x731)));
9904 evalcond[1]=(sj5+((new_r11*x731)));
9905 evalcond[2]=(cj5+(((-1.0)*new_r11*x734)));
9906 evalcond[3]=(((new_r00*x732))+(((-1.0)*cj5)));
9907 evalcond[4]=(((cj5*x731))+((sj5*x732)));
9908 evalcond[5]=((((-1.0)*x735))+x733+new_r00);
9909 evalcond[6]=((((-1.0)*x735))+x733+new_r11);
9910 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9911 {
9912 continue;
9913 }
9914 }
9915 
9916 {
9917 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9918 vinfos[0].jointtype = 1;
9919 vinfos[0].foffset = j0;
9920 vinfos[0].indices[0] = _ij0[0];
9921 vinfos[0].indices[1] = _ij0[1];
9922 vinfos[0].maxsolutions = _nj0;
9923 vinfos[1].jointtype = 1;
9924 vinfos[1].foffset = j1;
9925 vinfos[1].indices[0] = _ij1[0];
9926 vinfos[1].indices[1] = _ij1[1];
9927 vinfos[1].maxsolutions = _nj1;
9928 vinfos[2].jointtype = 1;
9929 vinfos[2].foffset = j2;
9930 vinfos[2].indices[0] = _ij2[0];
9931 vinfos[2].indices[1] = _ij2[1];
9932 vinfos[2].maxsolutions = _nj2;
9933 vinfos[3].jointtype = 1;
9934 vinfos[3].foffset = j3;
9935 vinfos[3].indices[0] = _ij3[0];
9936 vinfos[3].indices[1] = _ij3[1];
9937 vinfos[3].maxsolutions = _nj3;
9938 vinfos[4].jointtype = 1;
9939 vinfos[4].foffset = j4;
9940 vinfos[4].indices[0] = _ij4[0];
9941 vinfos[4].indices[1] = _ij4[1];
9942 vinfos[4].maxsolutions = _nj4;
9943 vinfos[5].jointtype = 1;
9944 vinfos[5].foffset = j5;
9945 vinfos[5].indices[0] = _ij5[0];
9946 vinfos[5].indices[1] = _ij5[1];
9947 vinfos[5].maxsolutions = _nj5;
9948 std::vector<int> vfree(0);
9949 solutions.AddSolution(vinfos,vfree);
9950 }
9951 }
9952 }
9953 
9954 }
9955 
9956 }
9957 
9958 } else
9959 {
9960 {
9961 IkReal j3array[1], cj3array[1], sj3array[1];
9962 bool j3valid[1]={false};
9963 _nj3 = 1;
9965 if(!x736.valid){
9966 continue;
9967 }
9968 CheckValue<IkReal> x737 = IKatan2WithCheck(IkReal(((-1.0)*sj5)),IkReal(cj5),IKFAST_ATAN2_MAGTHRESH);
9969 if(!x737.valid){
9970 continue;
9971 }
9972 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x736.value)))+(x737.value));
9973 sj3array[0]=IKsin(j3array[0]);
9974 cj3array[0]=IKcos(j3array[0]);
9975 if( j3array[0] > IKPI )
9976 {
9977  j3array[0]-=IK2PI;
9978 }
9979 else if( j3array[0] < -IKPI )
9980 { j3array[0]+=IK2PI;
9981 }
9982 j3valid[0] = true;
9983 for(int ij3 = 0; ij3 < 1; ++ij3)
9984 {
9985 if( !j3valid[ij3] )
9986 {
9987  continue;
9988 }
9989 _ij3[0] = ij3; _ij3[1] = -1;
9990 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
9991 {
9992 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
9993 {
9994  j3valid[iij3]=false; _ij3[1] = iij3; break;
9995 }
9996 }
9997 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
9998 {
9999 IkReal evalcond[7];
10000 IkReal x738=IKsin(j3);
10001 IkReal x739=IKcos(j3);
10002 IkReal x740=(sj5*x738);
10003 IkReal x741=((1.0)*x739);
10004 IkReal x742=(cj5*x741);
10005 evalcond[0]=(sj5+((new_r00*x738)));
10006 evalcond[1]=(sj5+((new_r11*x738)));
10007 evalcond[2]=(cj5+(((-1.0)*new_r11*x741)));
10008 evalcond[3]=(((new_r00*x739))+(((-1.0)*cj5)));
10009 evalcond[4]=(((cj5*x738))+((sj5*x739)));
10010 evalcond[5]=(x740+new_r00+(((-1.0)*x742)));
10011 evalcond[6]=(x740+new_r11+(((-1.0)*x742)));
10012 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
10013 {
10014 continue;
10015 }
10016 }
10017 
10018 {
10019 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10020 vinfos[0].jointtype = 1;
10021 vinfos[0].foffset = j0;
10022 vinfos[0].indices[0] = _ij0[0];
10023 vinfos[0].indices[1] = _ij0[1];
10024 vinfos[0].maxsolutions = _nj0;
10025 vinfos[1].jointtype = 1;
10026 vinfos[1].foffset = j1;
10027 vinfos[1].indices[0] = _ij1[0];
10028 vinfos[1].indices[1] = _ij1[1];
10029 vinfos[1].maxsolutions = _nj1;
10030 vinfos[2].jointtype = 1;
10031 vinfos[2].foffset = j2;
10032 vinfos[2].indices[0] = _ij2[0];
10033 vinfos[2].indices[1] = _ij2[1];
10034 vinfos[2].maxsolutions = _nj2;
10035 vinfos[3].jointtype = 1;
10036 vinfos[3].foffset = j3;
10037 vinfos[3].indices[0] = _ij3[0];
10038 vinfos[3].indices[1] = _ij3[1];
10039 vinfos[3].maxsolutions = _nj3;
10040 vinfos[4].jointtype = 1;
10041 vinfos[4].foffset = j4;
10042 vinfos[4].indices[0] = _ij4[0];
10043 vinfos[4].indices[1] = _ij4[1];
10044 vinfos[4].maxsolutions = _nj4;
10045 vinfos[5].jointtype = 1;
10046 vinfos[5].foffset = j5;
10047 vinfos[5].indices[0] = _ij5[0];
10048 vinfos[5].indices[1] = _ij5[1];
10049 vinfos[5].maxsolutions = _nj5;
10050 std::vector<int> vfree(0);
10051 solutions.AddSolution(vinfos,vfree);
10052 }
10053 }
10054 }
10055 
10056 }
10057 
10058 }
10059 
10060 }
10061 } while(0);
10062 if( bgotonextstatement )
10063 {
10064 bool bgotonextstatement = true;
10065 do
10066 {
10067 if( 1 )
10068 {
10069 bgotonextstatement=false;
10070 continue; // branch miss [j3]
10071 
10072 }
10073 } while(0);
10074 if( bgotonextstatement )
10075 {
10076 }
10077 }
10078 }
10079 }
10080 }
10081 }
10082 }
10083 }
10084 }
10085 }
10086 
10087 } else
10088 {
10089 {
10090 IkReal j3array[1], cj3array[1], sj3array[1];
10091 bool j3valid[1]={false};
10092 _nj3 = 1;
10093 IkReal x743=((1.0)*new_r11);
10094 CheckValue<IkReal> x744 = IKatan2WithCheck(IkReal((((new_r00*new_r01))+((cj5*sj5)))),IkReal(((1.0)+(((-1.0)*new_r00*x743))+(((-1.0)*(cj5*cj5))))),IKFAST_ATAN2_MAGTHRESH);
10095 if(!x744.valid){
10096 continue;
10097 }
10098 CheckValue<IkReal> x745=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r01*sj5))+(((-1.0)*cj5*x743)))),-1);
10099 if(!x745.valid){
10100 continue;
10101 }
10102 j3array[0]=((-1.5707963267949)+(x744.value)+(((1.5707963267949)*(x745.value))));
10103 sj3array[0]=IKsin(j3array[0]);
10104 cj3array[0]=IKcos(j3array[0]);
10105 if( j3array[0] > IKPI )
10106 {
10107  j3array[0]-=IK2PI;
10108 }
10109 else if( j3array[0] < -IKPI )
10110 { j3array[0]+=IK2PI;
10111 }
10112 j3valid[0] = true;
10113 for(int ij3 = 0; ij3 < 1; ++ij3)
10114 {
10115 if( !j3valid[ij3] )
10116 {
10117  continue;
10118 }
10119 _ij3[0] = ij3; _ij3[1] = -1;
10120 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
10121 {
10122 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10123 {
10124  j3valid[iij3]=false; _ij3[1] = iij3; break;
10125 }
10126 }
10127 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10128 {
10129 IkReal evalcond[8];
10130 IkReal x746=IKcos(j3);
10131 IkReal x747=IKsin(j3);
10132 IkReal x748=(sj5*x747);
10133 IkReal x749=(cj5*x747);
10134 IkReal x750=(sj5*x746);
10135 IkReal x751=((1.0)*x746);
10136 IkReal x752=(cj5*x751);
10137 evalcond[0]=(sj5+((new_r01*x746))+((new_r11*x747)));
10138 evalcond[1]=(x750+x749+new_r01);
10139 evalcond[2]=(sj5+(((-1.0)*new_r10*x751))+((new_r00*x747)));
10140 evalcond[3]=(cj5+(((-1.0)*new_r11*x751))+((new_r01*x747)));
10141 evalcond[4]=(x748+new_r00+(((-1.0)*x752)));
10142 evalcond[5]=(x748+new_r11+(((-1.0)*x752)));
10143 evalcond[6]=(((new_r10*x747))+((new_r00*x746))+(((-1.0)*cj5)));
10144 evalcond[7]=((((-1.0)*x750))+(((-1.0)*x749))+new_r10);
10145 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
10146 {
10147 continue;
10148 }
10149 }
10150 
10151 {
10152 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10153 vinfos[0].jointtype = 1;
10154 vinfos[0].foffset = j0;
10155 vinfos[0].indices[0] = _ij0[0];
10156 vinfos[0].indices[1] = _ij0[1];
10157 vinfos[0].maxsolutions = _nj0;
10158 vinfos[1].jointtype = 1;
10159 vinfos[1].foffset = j1;
10160 vinfos[1].indices[0] = _ij1[0];
10161 vinfos[1].indices[1] = _ij1[1];
10162 vinfos[1].maxsolutions = _nj1;
10163 vinfos[2].jointtype = 1;
10164 vinfos[2].foffset = j2;
10165 vinfos[2].indices[0] = _ij2[0];
10166 vinfos[2].indices[1] = _ij2[1];
10167 vinfos[2].maxsolutions = _nj2;
10168 vinfos[3].jointtype = 1;
10169 vinfos[3].foffset = j3;
10170 vinfos[3].indices[0] = _ij3[0];
10171 vinfos[3].indices[1] = _ij3[1];
10172 vinfos[3].maxsolutions = _nj3;
10173 vinfos[4].jointtype = 1;
10174 vinfos[4].foffset = j4;
10175 vinfos[4].indices[0] = _ij4[0];
10176 vinfos[4].indices[1] = _ij4[1];
10177 vinfos[4].maxsolutions = _nj4;
10178 vinfos[5].jointtype = 1;
10179 vinfos[5].foffset = j5;
10180 vinfos[5].indices[0] = _ij5[0];
10181 vinfos[5].indices[1] = _ij5[1];
10182 vinfos[5].maxsolutions = _nj5;
10183 std::vector<int> vfree(0);
10184 solutions.AddSolution(vinfos,vfree);
10185 }
10186 }
10187 }
10188 
10189 }
10190 
10191 }
10192 
10193 } else
10194 {
10195 {
10196 IkReal j3array[1], cj3array[1], sj3array[1];
10197 bool j3valid[1]={false};
10198 _nj3 = 1;
10199 CheckValue<IkReal> x753 = IKatan2WithCheck(IkReal((((new_r11*sj5))+((cj5*new_r01)))),IkReal((((new_r01*sj5))+(((-1.0)*cj5*new_r11)))),IKFAST_ATAN2_MAGTHRESH);
10200 if(!x753.valid){
10201 continue;
10202 }
10203 CheckValue<IkReal> x754=IKPowWithIntegerCheck(IKsign(((((-1.0)*(new_r01*new_r01)))+(((-1.0)*(new_r11*new_r11))))),-1);
10204 if(!x754.valid){
10205 continue;
10206 }
10207 j3array[0]=((-1.5707963267949)+(x753.value)+(((1.5707963267949)*(x754.value))));
10208 sj3array[0]=IKsin(j3array[0]);
10209 cj3array[0]=IKcos(j3array[0]);
10210 if( j3array[0] > IKPI )
10211 {
10212  j3array[0]-=IK2PI;
10213 }
10214 else if( j3array[0] < -IKPI )
10215 { j3array[0]+=IK2PI;
10216 }
10217 j3valid[0] = true;
10218 for(int ij3 = 0; ij3 < 1; ++ij3)
10219 {
10220 if( !j3valid[ij3] )
10221 {
10222  continue;
10223 }
10224 _ij3[0] = ij3; _ij3[1] = -1;
10225 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
10226 {
10227 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10228 {
10229  j3valid[iij3]=false; _ij3[1] = iij3; break;
10230 }
10231 }
10232 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10233 {
10234 IkReal evalcond[8];
10235 IkReal x755=IKcos(j3);
10236 IkReal x756=IKsin(j3);
10237 IkReal x757=(sj5*x756);
10238 IkReal x758=(cj5*x756);
10239 IkReal x759=(sj5*x755);
10240 IkReal x760=((1.0)*x755);
10241 IkReal x761=(cj5*x760);
10242 evalcond[0]=(sj5+((new_r11*x756))+((new_r01*x755)));
10243 evalcond[1]=(x759+x758+new_r01);
10244 evalcond[2]=(sj5+(((-1.0)*new_r10*x760))+((new_r00*x756)));
10245 evalcond[3]=(cj5+(((-1.0)*new_r11*x760))+((new_r01*x756)));
10246 evalcond[4]=((((-1.0)*x761))+x757+new_r00);
10247 evalcond[5]=((((-1.0)*x761))+x757+new_r11);
10248 evalcond[6]=(((new_r00*x755))+((new_r10*x756))+(((-1.0)*cj5)));
10249 evalcond[7]=((((-1.0)*x759))+(((-1.0)*x758))+new_r10);
10250 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
10251 {
10252 continue;
10253 }
10254 }
10255 
10256 {
10257 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10258 vinfos[0].jointtype = 1;
10259 vinfos[0].foffset = j0;
10260 vinfos[0].indices[0] = _ij0[0];
10261 vinfos[0].indices[1] = _ij0[1];
10262 vinfos[0].maxsolutions = _nj0;
10263 vinfos[1].jointtype = 1;
10264 vinfos[1].foffset = j1;
10265 vinfos[1].indices[0] = _ij1[0];
10266 vinfos[1].indices[1] = _ij1[1];
10267 vinfos[1].maxsolutions = _nj1;
10268 vinfos[2].jointtype = 1;
10269 vinfos[2].foffset = j2;
10270 vinfos[2].indices[0] = _ij2[0];
10271 vinfos[2].indices[1] = _ij2[1];
10272 vinfos[2].maxsolutions = _nj2;
10273 vinfos[3].jointtype = 1;
10274 vinfos[3].foffset = j3;
10275 vinfos[3].indices[0] = _ij3[0];
10276 vinfos[3].indices[1] = _ij3[1];
10277 vinfos[3].maxsolutions = _nj3;
10278 vinfos[4].jointtype = 1;
10279 vinfos[4].foffset = j4;
10280 vinfos[4].indices[0] = _ij4[0];
10281 vinfos[4].indices[1] = _ij4[1];
10282 vinfos[4].maxsolutions = _nj4;
10283 vinfos[5].jointtype = 1;
10284 vinfos[5].foffset = j5;
10285 vinfos[5].indices[0] = _ij5[0];
10286 vinfos[5].indices[1] = _ij5[1];
10287 vinfos[5].maxsolutions = _nj5;
10288 std::vector<int> vfree(0);
10289 solutions.AddSolution(vinfos,vfree);
10290 }
10291 }
10292 }
10293 
10294 }
10295 
10296 }
10297 
10298 } else
10299 {
10300 {
10301 IkReal j3array[1], cj3array[1], sj3array[1];
10302 bool j3valid[1]={false};
10303 _nj3 = 1;
10304 IkReal x762=((1.0)*new_r11);
10305 CheckValue<IkReal> x763 = IKatan2WithCheck(IkReal((((new_r10*sj5))+((new_r01*sj5)))),IkReal((((new_r00*sj5))+(((-1.0)*sj5*x762)))),IKFAST_ATAN2_MAGTHRESH);
10306 if(!x763.valid){
10307 continue;
10308 }
10309 CheckValue<IkReal> x764=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x762))+(((-1.0)*new_r00*new_r01)))),-1);
10310 if(!x764.valid){
10311 continue;
10312 }
10313 j3array[0]=((-1.5707963267949)+(x763.value)+(((1.5707963267949)*(x764.value))));
10314 sj3array[0]=IKsin(j3array[0]);
10315 cj3array[0]=IKcos(j3array[0]);
10316 if( j3array[0] > IKPI )
10317 {
10318  j3array[0]-=IK2PI;
10319 }
10320 else if( j3array[0] < -IKPI )
10321 { j3array[0]+=IK2PI;
10322 }
10323 j3valid[0] = true;
10324 for(int ij3 = 0; ij3 < 1; ++ij3)
10325 {
10326 if( !j3valid[ij3] )
10327 {
10328  continue;
10329 }
10330 _ij3[0] = ij3; _ij3[1] = -1;
10331 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
10332 {
10333 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10334 {
10335  j3valid[iij3]=false; _ij3[1] = iij3; break;
10336 }
10337 }
10338 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10339 {
10340 IkReal evalcond[8];
10341 IkReal x765=IKcos(j3);
10342 IkReal x766=IKsin(j3);
10343 IkReal x767=(sj5*x766);
10344 IkReal x768=(cj5*x766);
10345 IkReal x769=(sj5*x765);
10346 IkReal x770=((1.0)*x765);
10347 IkReal x771=(cj5*x770);
10348 evalcond[0]=(sj5+((new_r11*x766))+((new_r01*x765)));
10349 evalcond[1]=(x768+x769+new_r01);
10350 evalcond[2]=(sj5+((new_r00*x766))+(((-1.0)*new_r10*x770)));
10351 evalcond[3]=(cj5+((new_r01*x766))+(((-1.0)*new_r11*x770)));
10352 evalcond[4]=(x767+(((-1.0)*x771))+new_r00);
10353 evalcond[5]=(x767+(((-1.0)*x771))+new_r11);
10354 evalcond[6]=(((new_r10*x766))+((new_r00*x765))+(((-1.0)*cj5)));
10355 evalcond[7]=((((-1.0)*x769))+(((-1.0)*x768))+new_r10);
10356 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
10357 {
10358 continue;
10359 }
10360 }
10361 
10362 {
10363 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10364 vinfos[0].jointtype = 1;
10365 vinfos[0].foffset = j0;
10366 vinfos[0].indices[0] = _ij0[0];
10367 vinfos[0].indices[1] = _ij0[1];
10368 vinfos[0].maxsolutions = _nj0;
10369 vinfos[1].jointtype = 1;
10370 vinfos[1].foffset = j1;
10371 vinfos[1].indices[0] = _ij1[0];
10372 vinfos[1].indices[1] = _ij1[1];
10373 vinfos[1].maxsolutions = _nj1;
10374 vinfos[2].jointtype = 1;
10375 vinfos[2].foffset = j2;
10376 vinfos[2].indices[0] = _ij2[0];
10377 vinfos[2].indices[1] = _ij2[1];
10378 vinfos[2].maxsolutions = _nj2;
10379 vinfos[3].jointtype = 1;
10380 vinfos[3].foffset = j3;
10381 vinfos[3].indices[0] = _ij3[0];
10382 vinfos[3].indices[1] = _ij3[1];
10383 vinfos[3].maxsolutions = _nj3;
10384 vinfos[4].jointtype = 1;
10385 vinfos[4].foffset = j4;
10386 vinfos[4].indices[0] = _ij4[0];
10387 vinfos[4].indices[1] = _ij4[1];
10388 vinfos[4].maxsolutions = _nj4;
10389 vinfos[5].jointtype = 1;
10390 vinfos[5].foffset = j5;
10391 vinfos[5].indices[0] = _ij5[0];
10392 vinfos[5].indices[1] = _ij5[1];
10393 vinfos[5].maxsolutions = _nj5;
10394 std::vector<int> vfree(0);
10395 solutions.AddSolution(vinfos,vfree);
10396 }
10397 }
10398 }
10399 
10400 }
10401 
10402 }
10403 
10404 }
10405 } while(0);
10406 if( bgotonextstatement )
10407 {
10408 bool bgotonextstatement = true;
10409 do
10410 {
10411 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959)));
10412 evalcond[1]=new_r02;
10413 evalcond[2]=new_r12;
10414 evalcond[3]=new_r21;
10415 evalcond[4]=new_r20;
10416 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
10417 {
10418 bgotonextstatement=false;
10419 {
10420 IkReal j3eval[3];
10421 sj4=0;
10422 cj4=-1.0;
10423 j4=3.14159265358979;
10424 IkReal x772=((1.0)*new_r10);
10425 IkReal x773=((((-1.0)*new_r11*x772))+(((-1.0)*new_r00*new_r01)));
10426 j3eval[0]=x773;
10427 j3eval[1]=((IKabs((((cj5*new_r11))+((cj5*new_r00)))))+(IKabs((((cj5*new_r01))+(((-1.0)*cj5*x772))))));
10428 j3eval[2]=IKsign(x773);
10429 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
10430 {
10431 {
10432 IkReal j3eval[3];
10433 sj4=0;
10434 cj4=-1.0;
10435 j4=3.14159265358979;
10436 IkReal x774=((1.0)*new_r10);
10437 IkReal x775=((((-1.0)*cj5*new_r00))+(((-1.0)*sj5*x774)));
10438 j3eval[0]=x775;
10439 j3eval[1]=IKsign(x775);
10440 j3eval[2]=((IKabs((((new_r00*new_r01))+((cj5*sj5)))))+(IKabs(((((-1.0)*new_r01*x774))+(cj5*cj5)))));
10441 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
10442 {
10443 {
10444 IkReal j3eval[3];
10445 sj4=0;
10446 cj4=-1.0;
10447 j4=3.14159265358979;
10448 IkReal x776=((1.0)*new_r00);
10449 IkReal x777=((((-1.0)*sj5*x776))+((cj5*new_r10)));
10450 j3eval[0]=x777;
10451 j3eval[1]=((IKabs((((cj5*sj5))+(((-1.0)*new_r10*x776)))))+(IKabs(((((-1.0)*(cj5*cj5)))+(new_r00*new_r00)))));
10452 j3eval[2]=IKsign(x777);
10453 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
10454 {
10455 {
10456 IkReal evalcond[1];
10457 bool bgotonextstatement = true;
10458 do
10459 {
10460 IkReal x778=((-1.0)*new_r00);
10461 IkReal x780 = ((new_r10*new_r10)+(new_r00*new_r00));
10462 if(IKabs(x780)==0){
10463 continue;
10464 }
10465 IkReal x779=pow(x780,-0.5);
10466 CheckValue<IkReal> x781 = IKatan2WithCheck(IkReal(new_r10),IkReal(x778),IKFAST_ATAN2_MAGTHRESH);
10467 if(!x781.valid){
10468 continue;
10469 }
10470 IkReal gconst6=((-1.0)*(x781.value));
10471 IkReal gconst7=((-1.0)*new_r10*x779);
10472 IkReal gconst8=(x778*x779);
10473 CheckValue<IkReal> x782 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
10474 if(!x782.valid){
10475 continue;
10476 }
10477 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs((j5+(x782.value))))), 6.28318530717959)));
10478 if( IKabs(evalcond[0]) < 0.0000050000000000 )
10479 {
10480 bgotonextstatement=false;
10481 {
10482 IkReal j3eval[3];
10483 IkReal x783=((-1.0)*new_r00);
10484 CheckValue<IkReal> x786 = IKatan2WithCheck(IkReal(new_r10),IkReal(x783),IKFAST_ATAN2_MAGTHRESH);
10485 if(!x786.valid){
10486 continue;
10487 }
10488 IkReal x784=((-1.0)*(x786.value));
10489 IkReal x785=x779;
10490 sj4=0;
10491 cj4=-1.0;
10492 j4=3.14159265358979;
10493 sj5=gconst7;
10494 cj5=gconst8;
10495 j5=x784;
10496 IkReal gconst6=x784;
10497 IkReal gconst7=((-1.0)*new_r10*x785);
10498 IkReal gconst8=(x783*x785);
10499 IkReal x787=new_r00*new_r00;
10500 IkReal x788=((1.0)*new_r11);
10501 IkReal x789=((1.0)*new_r00*new_r01);
10502 IkReal x790=((((-1.0)*x789))+(((-1.0)*new_r10*x788)));
10503 IkReal x791=x779;
10504 IkReal x792=(new_r00*x791);
10505 j3eval[0]=x790;
10506 j3eval[1]=((IKabs(((((-1.0)*x788*x792))+(((-1.0)*x787*x791)))))+(IKabs((((new_r10*x792))+(((-1.0)*x789*x791))))));
10507 j3eval[2]=IKsign(x790);
10508 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
10509 {
10510 {
10511 IkReal j3eval[1];
10512 IkReal x793=((-1.0)*new_r00);
10513 CheckValue<IkReal> x796 = IKatan2WithCheck(IkReal(new_r10),IkReal(x793),IKFAST_ATAN2_MAGTHRESH);
10514 if(!x796.valid){
10515 continue;
10516 }
10517 IkReal x794=((-1.0)*(x796.value));
10518 IkReal x795=x779;
10519 sj4=0;
10520 cj4=-1.0;
10521 j4=3.14159265358979;
10522 sj5=gconst7;
10523 cj5=gconst8;
10524 j5=x794;
10525 IkReal gconst6=x794;
10526 IkReal gconst7=((-1.0)*new_r10*x795);
10527 IkReal gconst8=(x793*x795);
10528 IkReal x797=new_r10*new_r10;
10529 IkReal x798=new_r00*new_r00;
10530 CheckValue<IkReal> x801=IKPowWithIntegerCheck((x797+x798),-1);
10531 if(!x801.valid){
10532 continue;
10533 }
10534 IkReal x799=x801.value;
10535 IkReal x800=(new_r00*x799);
10536 j3eval[0]=((IKabs((((new_r01*x797*x800))+((new_r10*x800))+((new_r01*x800*(new_r00*new_r00))))))+(IKabs((((x798*x799))+(((-1.0)*new_r01*new_r10))))));
10537 if( IKabs(j3eval[0]) < 0.0000010000000000 )
10538 {
10539 {
10540 IkReal j3eval[1];
10541 IkReal x802=((-1.0)*new_r00);
10542 CheckValue<IkReal> x805 = IKatan2WithCheck(IkReal(new_r10),IkReal(x802),IKFAST_ATAN2_MAGTHRESH);
10543 if(!x805.valid){
10544 continue;
10545 }
10546 IkReal x803=((-1.0)*(x805.value));
10547 IkReal x804=x779;
10548 sj4=0;
10549 cj4=-1.0;
10550 j4=3.14159265358979;
10551 sj5=gconst7;
10552 cj5=gconst8;
10553 j5=x803;
10554 IkReal gconst6=x803;
10555 IkReal gconst7=((-1.0)*new_r10*x804);
10556 IkReal gconst8=(x802*x804);
10557 IkReal x806=new_r00*new_r00;
10558 IkReal x807=new_r10*new_r10;
10559 CheckValue<IkReal> x811=IKPowWithIntegerCheck((x807+x806),-1);
10560 if(!x811.valid){
10561 continue;
10562 }
10563 IkReal x808=x811.value;
10564 IkReal x809=(new_r10*x808);
10565 IkReal x810=((1.0)*x808);
10566 j3eval[0]=((IKabs((((new_r00*x809*(new_r10*new_r10)))+((new_r00*x809))+((x809*(new_r00*new_r00*new_r00))))))+(IKabs((((x806*x808))+(((-1.0)*x810*(x807*x807)))+(((-1.0)*x806*x807*x810))))));
10567 if( IKabs(j3eval[0]) < 0.0000010000000000 )
10568 {
10569 {
10570 IkReal evalcond[2];
10571 bool bgotonextstatement = true;
10572 do
10573 {
10574 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
10575 if( IKabs(evalcond[0]) < 0.0000050000000000 )
10576 {
10577 bgotonextstatement=false;
10578 {
10579 IkReal j3eval[1];
10580 CheckValue<IkReal> x813 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
10581 if(!x813.valid){
10582 continue;
10583 }
10584 IkReal x812=((-1.0)*(x813.value));
10585 sj4=0;
10586 cj4=-1.0;
10587 j4=3.14159265358979;
10588 sj5=gconst7;
10589 cj5=gconst8;
10590 j5=x812;
10591 new_r11=0;
10592 new_r00=0;
10593 IkReal gconst6=x812;
10594 IkReal x814 = new_r10*new_r10;
10595 if(IKabs(x814)==0){
10596 continue;
10597 }
10598 IkReal gconst7=((-1.0)*new_r10*(pow(x814,-0.5)));
10599 IkReal gconst8=0;
10600 j3eval[0]=new_r10;
10601 if( IKabs(j3eval[0]) < 0.0000010000000000 )
10602 {
10603 {
10604 IkReal j3array[2], cj3array[2], sj3array[2];
10605 bool j3valid[2]={false};
10606 _nj3 = 2;
10607 CheckValue<IkReal> x815=IKPowWithIntegerCheck(gconst7,-1);
10608 if(!x815.valid){
10609 continue;
10610 }
10611 cj3array[0]=(new_r01*(x815.value));
10612 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
10613 {
10614  j3valid[0] = j3valid[1] = true;
10615  j3array[0] = IKacos(cj3array[0]);
10616  sj3array[0] = IKsin(j3array[0]);
10617  cj3array[1] = cj3array[0];
10618  j3array[1] = -j3array[0];
10619  sj3array[1] = -sj3array[0];
10620 }
10621 else if( isnan(cj3array[0]) )
10622 {
10623  // probably any value will work
10624  j3valid[0] = true;
10625  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
10626 }
10627 for(int ij3 = 0; ij3 < 2; ++ij3)
10628 {
10629 if( !j3valid[ij3] )
10630 {
10631  continue;
10632 }
10633 _ij3[0] = ij3; _ij3[1] = -1;
10634 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
10635 {
10636 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10637 {
10638  j3valid[iij3]=false; _ij3[1] = iij3; break;
10639 }
10640 }
10641 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10642 {
10643 IkReal evalcond[6];
10644 IkReal x816=IKsin(j3);
10645 IkReal x817=IKcos(j3);
10646 IkReal x818=((1.0)*gconst7);
10647 evalcond[0]=(new_r01*x816);
10648 evalcond[1]=(new_r10*x816);
10649 evalcond[2]=(gconst7*x816);
10650 evalcond[3]=((((-1.0)*new_r10*x817))+gconst7);
10651 evalcond[4]=((((-1.0)*x817*x818))+new_r10);
10652 evalcond[5]=(((new_r01*x817))+(((-1.0)*x818)));
10653 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
10654 {
10655 continue;
10656 }
10657 }
10658 
10659 {
10660 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10661 vinfos[0].jointtype = 1;
10662 vinfos[0].foffset = j0;
10663 vinfos[0].indices[0] = _ij0[0];
10664 vinfos[0].indices[1] = _ij0[1];
10665 vinfos[0].maxsolutions = _nj0;
10666 vinfos[1].jointtype = 1;
10667 vinfos[1].foffset = j1;
10668 vinfos[1].indices[0] = _ij1[0];
10669 vinfos[1].indices[1] = _ij1[1];
10670 vinfos[1].maxsolutions = _nj1;
10671 vinfos[2].jointtype = 1;
10672 vinfos[2].foffset = j2;
10673 vinfos[2].indices[0] = _ij2[0];
10674 vinfos[2].indices[1] = _ij2[1];
10675 vinfos[2].maxsolutions = _nj2;
10676 vinfos[3].jointtype = 1;
10677 vinfos[3].foffset = j3;
10678 vinfos[3].indices[0] = _ij3[0];
10679 vinfos[3].indices[1] = _ij3[1];
10680 vinfos[3].maxsolutions = _nj3;
10681 vinfos[4].jointtype = 1;
10682 vinfos[4].foffset = j4;
10683 vinfos[4].indices[0] = _ij4[0];
10684 vinfos[4].indices[1] = _ij4[1];
10685 vinfos[4].maxsolutions = _nj4;
10686 vinfos[5].jointtype = 1;
10687 vinfos[5].foffset = j5;
10688 vinfos[5].indices[0] = _ij5[0];
10689 vinfos[5].indices[1] = _ij5[1];
10690 vinfos[5].maxsolutions = _nj5;
10691 std::vector<int> vfree(0);
10692 solutions.AddSolution(vinfos,vfree);
10693 }
10694 }
10695 }
10696 
10697 } else
10698 {
10699 {
10700 IkReal j3array[2], cj3array[2], sj3array[2];
10701 bool j3valid[2]={false};
10702 _nj3 = 2;
10703 CheckValue<IkReal> x819=IKPowWithIntegerCheck(new_r10,-1);
10704 if(!x819.valid){
10705 continue;
10706 }
10707 cj3array[0]=(gconst7*(x819.value));
10708 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
10709 {
10710  j3valid[0] = j3valid[1] = true;
10711  j3array[0] = IKacos(cj3array[0]);
10712  sj3array[0] = IKsin(j3array[0]);
10713  cj3array[1] = cj3array[0];
10714  j3array[1] = -j3array[0];
10715  sj3array[1] = -sj3array[0];
10716 }
10717 else if( isnan(cj3array[0]) )
10718 {
10719  // probably any value will work
10720  j3valid[0] = true;
10721  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
10722 }
10723 for(int ij3 = 0; ij3 < 2; ++ij3)
10724 {
10725 if( !j3valid[ij3] )
10726 {
10727  continue;
10728 }
10729 _ij3[0] = ij3; _ij3[1] = -1;
10730 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
10731 {
10732 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10733 {
10734  j3valid[iij3]=false; _ij3[1] = iij3; break;
10735 }
10736 }
10737 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10738 {
10739 IkReal evalcond[6];
10740 IkReal x820=IKsin(j3);
10741 IkReal x821=IKcos(j3);
10742 IkReal x822=((1.0)*gconst7);
10743 IkReal x823=(x821*x822);
10744 evalcond[0]=(new_r01*x820);
10745 evalcond[1]=(new_r10*x820);
10746 evalcond[2]=(gconst7*x820);
10747 evalcond[3]=((((-1.0)*x823))+new_r01);
10748 evalcond[4]=((((-1.0)*x823))+new_r10);
10749 evalcond[5]=(((new_r01*x821))+(((-1.0)*x822)));
10750 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
10751 {
10752 continue;
10753 }
10754 }
10755 
10756 {
10757 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10758 vinfos[0].jointtype = 1;
10759 vinfos[0].foffset = j0;
10760 vinfos[0].indices[0] = _ij0[0];
10761 vinfos[0].indices[1] = _ij0[1];
10762 vinfos[0].maxsolutions = _nj0;
10763 vinfos[1].jointtype = 1;
10764 vinfos[1].foffset = j1;
10765 vinfos[1].indices[0] = _ij1[0];
10766 vinfos[1].indices[1] = _ij1[1];
10767 vinfos[1].maxsolutions = _nj1;
10768 vinfos[2].jointtype = 1;
10769 vinfos[2].foffset = j2;
10770 vinfos[2].indices[0] = _ij2[0];
10771 vinfos[2].indices[1] = _ij2[1];
10772 vinfos[2].maxsolutions = _nj2;
10773 vinfos[3].jointtype = 1;
10774 vinfos[3].foffset = j3;
10775 vinfos[3].indices[0] = _ij3[0];
10776 vinfos[3].indices[1] = _ij3[1];
10777 vinfos[3].maxsolutions = _nj3;
10778 vinfos[4].jointtype = 1;
10779 vinfos[4].foffset = j4;
10780 vinfos[4].indices[0] = _ij4[0];
10781 vinfos[4].indices[1] = _ij4[1];
10782 vinfos[4].maxsolutions = _nj4;
10783 vinfos[5].jointtype = 1;
10784 vinfos[5].foffset = j5;
10785 vinfos[5].indices[0] = _ij5[0];
10786 vinfos[5].indices[1] = _ij5[1];
10787 vinfos[5].maxsolutions = _nj5;
10788 std::vector<int> vfree(0);
10789 solutions.AddSolution(vinfos,vfree);
10790 }
10791 }
10792 }
10793 
10794 }
10795 
10796 }
10797 
10798 }
10799 } while(0);
10800 if( bgotonextstatement )
10801 {
10802 bool bgotonextstatement = true;
10803 do
10804 {
10805 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
10806 evalcond[1]=gconst8;
10807 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
10808 {
10809 bgotonextstatement=false;
10810 {
10811 IkReal j3eval[3];
10812 IkReal x824=((-1.0)*new_r00);
10813 CheckValue<IkReal> x826 = IKatan2WithCheck(IkReal(new_r10),IkReal(x824),IKFAST_ATAN2_MAGTHRESH);
10814 if(!x826.valid){
10815 continue;
10816 }
10817 IkReal x825=((-1.0)*(x826.value));
10818 sj4=0;
10819 cj4=-1.0;
10820 j4=3.14159265358979;
10821 sj5=gconst7;
10822 cj5=gconst8;
10823 j5=x825;
10824 new_r11=0;
10825 new_r01=0;
10826 new_r22=0;
10827 new_r20=0;
10828 IkReal gconst6=x825;
10829 IkReal gconst7=((-1.0)*new_r10);
10830 IkReal gconst8=x824;
10831 j3eval[0]=1.0;
10832 j3eval[1]=1.0;
10833 j3eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10))));
10834 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
10835 {
10836 {
10837 IkReal j3eval[3];
10838 IkReal x827=((-1.0)*new_r00);
10839 CheckValue<IkReal> x829 = IKatan2WithCheck(IkReal(new_r10),IkReal(x827),IKFAST_ATAN2_MAGTHRESH);
10840 if(!x829.valid){
10841 continue;
10842 }
10843 IkReal x828=((-1.0)*(x829.value));
10844 sj4=0;
10845 cj4=-1.0;
10846 j4=3.14159265358979;
10847 sj5=gconst7;
10848 cj5=gconst8;
10849 j5=x828;
10850 new_r11=0;
10851 new_r01=0;
10852 new_r22=0;
10853 new_r20=0;
10854 IkReal gconst6=x828;
10855 IkReal gconst7=((-1.0)*new_r10);
10856 IkReal gconst8=x827;
10857 j3eval[0]=-1.0;
10858 j3eval[1]=((IKabs(((-1.0)+(new_r10*new_r10))))+(IKabs((new_r00*new_r10))));
10859 j3eval[2]=-1.0;
10860 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
10861 {
10862 {
10863 IkReal j3eval[3];
10864 IkReal x830=((-1.0)*new_r00);
10865 CheckValue<IkReal> x832 = IKatan2WithCheck(IkReal(new_r10),IkReal(x830),IKFAST_ATAN2_MAGTHRESH);
10866 if(!x832.valid){
10867 continue;
10868 }
10869 IkReal x831=((-1.0)*(x832.value));
10870 sj4=0;
10871 cj4=-1.0;
10872 j4=3.14159265358979;
10873 sj5=gconst7;
10874 cj5=gconst8;
10875 j5=x831;
10876 new_r11=0;
10877 new_r01=0;
10878 new_r22=0;
10879 new_r20=0;
10880 IkReal gconst6=x831;
10881 IkReal gconst7=((-1.0)*new_r10);
10882 IkReal gconst8=x830;
10883 j3eval[0]=1.0;
10884 j3eval[1]=((((0.5)*(IKabs(((1.0)+(((-2.0)*(new_r10*new_r10))))))))+(IKabs((new_r00*new_r10))));
10885 j3eval[2]=1.0;
10886 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
10887 {
10888 continue; // 3 cases reached
10889 
10890 } else
10891 {
10892 {
10893 IkReal j3array[1], cj3array[1], sj3array[1];
10894 bool j3valid[1]={false};
10895 _nj3 = 1;
10896 CheckValue<IkReal> x833=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst7*new_r10))+(((-1.0)*gconst8*new_r00)))),-1);
10897 if(!x833.valid){
10898 continue;
10899 }
10900 CheckValue<IkReal> x834 = IKatan2WithCheck(IkReal((((new_r00*new_r10))+((gconst7*gconst8)))),IkReal(((gconst8*gconst8)+(((-1.0)*(new_r10*new_r10))))),IKFAST_ATAN2_MAGTHRESH);
10901 if(!x834.valid){
10902 continue;
10903 }
10904 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x833.value)))+(x834.value));
10905 sj3array[0]=IKsin(j3array[0]);
10906 cj3array[0]=IKcos(j3array[0]);
10907 if( j3array[0] > IKPI )
10908 {
10909  j3array[0]-=IK2PI;
10910 }
10911 else if( j3array[0] < -IKPI )
10912 { j3array[0]+=IK2PI;
10913 }
10914 j3valid[0] = true;
10915 for(int ij3 = 0; ij3 < 1; ++ij3)
10916 {
10917 if( !j3valid[ij3] )
10918 {
10919  continue;
10920 }
10921 _ij3[0] = ij3; _ij3[1] = -1;
10922 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
10923 {
10924 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10925 {
10926  j3valid[iij3]=false; _ij3[1] = iij3; break;
10927 }
10928 }
10929 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10930 {
10931 IkReal evalcond[6];
10932 IkReal x835=IKsin(j3);
10933 IkReal x836=IKcos(j3);
10934 IkReal x837=(gconst8*x835);
10935 IkReal x838=(gconst7*x835);
10936 IkReal x839=(gconst8*x836);
10937 IkReal x840=((1.0)*x836);
10938 IkReal x841=(gconst7*x840);
10939 evalcond[0]=((((-1.0)*x841))+x837);
10940 evalcond[1]=(gconst8+((new_r00*x836))+((new_r10*x835)));
10941 evalcond[2]=(new_r00+x838+x839);
10942 evalcond[3]=((((-1.0)*new_r10*x840))+gconst7+((new_r00*x835)));
10943 evalcond[4]=((((-1.0)*x838))+(((-1.0)*x839)));
10944 evalcond[5]=((((-1.0)*x841))+new_r10+x837);
10945 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
10946 {
10947 continue;
10948 }
10949 }
10950 
10951 {
10952 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10953 vinfos[0].jointtype = 1;
10954 vinfos[0].foffset = j0;
10955 vinfos[0].indices[0] = _ij0[0];
10956 vinfos[0].indices[1] = _ij0[1];
10957 vinfos[0].maxsolutions = _nj0;
10958 vinfos[1].jointtype = 1;
10959 vinfos[1].foffset = j1;
10960 vinfos[1].indices[0] = _ij1[0];
10961 vinfos[1].indices[1] = _ij1[1];
10962 vinfos[1].maxsolutions = _nj1;
10963 vinfos[2].jointtype = 1;
10964 vinfos[2].foffset = j2;
10965 vinfos[2].indices[0] = _ij2[0];
10966 vinfos[2].indices[1] = _ij2[1];
10967 vinfos[2].maxsolutions = _nj2;
10968 vinfos[3].jointtype = 1;
10969 vinfos[3].foffset = j3;
10970 vinfos[3].indices[0] = _ij3[0];
10971 vinfos[3].indices[1] = _ij3[1];
10972 vinfos[3].maxsolutions = _nj3;
10973 vinfos[4].jointtype = 1;
10974 vinfos[4].foffset = j4;
10975 vinfos[4].indices[0] = _ij4[0];
10976 vinfos[4].indices[1] = _ij4[1];
10977 vinfos[4].maxsolutions = _nj4;
10978 vinfos[5].jointtype = 1;
10979 vinfos[5].foffset = j5;
10980 vinfos[5].indices[0] = _ij5[0];
10981 vinfos[5].indices[1] = _ij5[1];
10982 vinfos[5].maxsolutions = _nj5;
10983 std::vector<int> vfree(0);
10984 solutions.AddSolution(vinfos,vfree);
10985 }
10986 }
10987 }
10988 
10989 }
10990 
10991 }
10992 
10993 } else
10994 {
10995 {
10996 IkReal j3array[1], cj3array[1], sj3array[1];
10997 bool j3valid[1]={false};
10998 _nj3 = 1;
10999 CheckValue<IkReal> x842 = IKatan2WithCheck(IkReal((gconst7*new_r00)),IkReal((gconst8*new_r00)),IKFAST_ATAN2_MAGTHRESH);
11000 if(!x842.valid){
11001 continue;
11002 }
11003 CheckValue<IkReal> x843=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst8*gconst8)))+(((-1.0)*(gconst7*gconst7))))),-1);
11004 if(!x843.valid){
11005 continue;
11006 }
11007 j3array[0]=((-1.5707963267949)+(x842.value)+(((1.5707963267949)*(x843.value))));
11008 sj3array[0]=IKsin(j3array[0]);
11009 cj3array[0]=IKcos(j3array[0]);
11010 if( j3array[0] > IKPI )
11011 {
11012  j3array[0]-=IK2PI;
11013 }
11014 else if( j3array[0] < -IKPI )
11015 { j3array[0]+=IK2PI;
11016 }
11017 j3valid[0] = true;
11018 for(int ij3 = 0; ij3 < 1; ++ij3)
11019 {
11020 if( !j3valid[ij3] )
11021 {
11022  continue;
11023 }
11024 _ij3[0] = ij3; _ij3[1] = -1;
11025 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11026 {
11027 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11028 {
11029  j3valid[iij3]=false; _ij3[1] = iij3; break;
11030 }
11031 }
11032 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11033 {
11034 IkReal evalcond[6];
11035 IkReal x844=IKsin(j3);
11036 IkReal x845=IKcos(j3);
11037 IkReal x846=(gconst8*x844);
11038 IkReal x847=(gconst7*x844);
11039 IkReal x848=(gconst8*x845);
11040 IkReal x849=((1.0)*x845);
11041 IkReal x850=(gconst7*x849);
11042 evalcond[0]=((((-1.0)*x850))+x846);
11043 evalcond[1]=(((new_r10*x844))+gconst8+((new_r00*x845)));
11044 evalcond[2]=(new_r00+x847+x848);
11045 evalcond[3]=((((-1.0)*new_r10*x849))+gconst7+((new_r00*x844)));
11046 evalcond[4]=((((-1.0)*x848))+(((-1.0)*x847)));
11047 evalcond[5]=((((-1.0)*x850))+new_r10+x846);
11048 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
11049 {
11050 continue;
11051 }
11052 }
11053 
11054 {
11055 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11056 vinfos[0].jointtype = 1;
11057 vinfos[0].foffset = j0;
11058 vinfos[0].indices[0] = _ij0[0];
11059 vinfos[0].indices[1] = _ij0[1];
11060 vinfos[0].maxsolutions = _nj0;
11061 vinfos[1].jointtype = 1;
11062 vinfos[1].foffset = j1;
11063 vinfos[1].indices[0] = _ij1[0];
11064 vinfos[1].indices[1] = _ij1[1];
11065 vinfos[1].maxsolutions = _nj1;
11066 vinfos[2].jointtype = 1;
11067 vinfos[2].foffset = j2;
11068 vinfos[2].indices[0] = _ij2[0];
11069 vinfos[2].indices[1] = _ij2[1];
11070 vinfos[2].maxsolutions = _nj2;
11071 vinfos[3].jointtype = 1;
11072 vinfos[3].foffset = j3;
11073 vinfos[3].indices[0] = _ij3[0];
11074 vinfos[3].indices[1] = _ij3[1];
11075 vinfos[3].maxsolutions = _nj3;
11076 vinfos[4].jointtype = 1;
11077 vinfos[4].foffset = j4;
11078 vinfos[4].indices[0] = _ij4[0];
11079 vinfos[4].indices[1] = _ij4[1];
11080 vinfos[4].maxsolutions = _nj4;
11081 vinfos[5].jointtype = 1;
11082 vinfos[5].foffset = j5;
11083 vinfos[5].indices[0] = _ij5[0];
11084 vinfos[5].indices[1] = _ij5[1];
11085 vinfos[5].maxsolutions = _nj5;
11086 std::vector<int> vfree(0);
11087 solutions.AddSolution(vinfos,vfree);
11088 }
11089 }
11090 }
11091 
11092 }
11093 
11094 }
11095 
11096 } else
11097 {
11098 {
11099 IkReal j3array[1], cj3array[1], sj3array[1];
11100 bool j3valid[1]={false};
11101 _nj3 = 1;
11102 CheckValue<IkReal> x851 = IKatan2WithCheck(IkReal((gconst7*gconst8)),IkReal(gconst8*gconst8),IKFAST_ATAN2_MAGTHRESH);
11103 if(!x851.valid){
11104 continue;
11105 }
11106 CheckValue<IkReal> x852=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst7*new_r10))+(((-1.0)*gconst8*new_r00)))),-1);
11107 if(!x852.valid){
11108 continue;
11109 }
11110 j3array[0]=((-1.5707963267949)+(x851.value)+(((1.5707963267949)*(x852.value))));
11111 sj3array[0]=IKsin(j3array[0]);
11112 cj3array[0]=IKcos(j3array[0]);
11113 if( j3array[0] > IKPI )
11114 {
11115  j3array[0]-=IK2PI;
11116 }
11117 else if( j3array[0] < -IKPI )
11118 { j3array[0]+=IK2PI;
11119 }
11120 j3valid[0] = true;
11121 for(int ij3 = 0; ij3 < 1; ++ij3)
11122 {
11123 if( !j3valid[ij3] )
11124 {
11125  continue;
11126 }
11127 _ij3[0] = ij3; _ij3[1] = -1;
11128 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11129 {
11130 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11131 {
11132  j3valid[iij3]=false; _ij3[1] = iij3; break;
11133 }
11134 }
11135 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11136 {
11137 IkReal evalcond[6];
11138 IkReal x853=IKsin(j3);
11139 IkReal x854=IKcos(j3);
11140 IkReal x855=(gconst8*x853);
11141 IkReal x856=(gconst7*x853);
11142 IkReal x857=(gconst8*x854);
11143 IkReal x858=((1.0)*x854);
11144 IkReal x859=(gconst7*x858);
11145 evalcond[0]=((((-1.0)*x859))+x855);
11146 evalcond[1]=(gconst8+((new_r10*x853))+((new_r00*x854)));
11147 evalcond[2]=(new_r00+x856+x857);
11148 evalcond[3]=(gconst7+(((-1.0)*new_r10*x858))+((new_r00*x853)));
11149 evalcond[4]=((((-1.0)*x856))+(((-1.0)*x857)));
11150 evalcond[5]=((((-1.0)*x859))+new_r10+x855);
11151 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
11152 {
11153 continue;
11154 }
11155 }
11156 
11157 {
11158 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11159 vinfos[0].jointtype = 1;
11160 vinfos[0].foffset = j0;
11161 vinfos[0].indices[0] = _ij0[0];
11162 vinfos[0].indices[1] = _ij0[1];
11163 vinfos[0].maxsolutions = _nj0;
11164 vinfos[1].jointtype = 1;
11165 vinfos[1].foffset = j1;
11166 vinfos[1].indices[0] = _ij1[0];
11167 vinfos[1].indices[1] = _ij1[1];
11168 vinfos[1].maxsolutions = _nj1;
11169 vinfos[2].jointtype = 1;
11170 vinfos[2].foffset = j2;
11171 vinfos[2].indices[0] = _ij2[0];
11172 vinfos[2].indices[1] = _ij2[1];
11173 vinfos[2].maxsolutions = _nj2;
11174 vinfos[3].jointtype = 1;
11175 vinfos[3].foffset = j3;
11176 vinfos[3].indices[0] = _ij3[0];
11177 vinfos[3].indices[1] = _ij3[1];
11178 vinfos[3].maxsolutions = _nj3;
11179 vinfos[4].jointtype = 1;
11180 vinfos[4].foffset = j4;
11181 vinfos[4].indices[0] = _ij4[0];
11182 vinfos[4].indices[1] = _ij4[1];
11183 vinfos[4].maxsolutions = _nj4;
11184 vinfos[5].jointtype = 1;
11185 vinfos[5].foffset = j5;
11186 vinfos[5].indices[0] = _ij5[0];
11187 vinfos[5].indices[1] = _ij5[1];
11188 vinfos[5].maxsolutions = _nj5;
11189 std::vector<int> vfree(0);
11190 solutions.AddSolution(vinfos,vfree);
11191 }
11192 }
11193 }
11194 
11195 }
11196 
11197 }
11198 
11199 }
11200 } while(0);
11201 if( bgotonextstatement )
11202 {
11203 bool bgotonextstatement = true;
11204 do
11205 {
11206 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
11207 if( IKabs(evalcond[0]) < 0.0000050000000000 )
11208 {
11209 bgotonextstatement=false;
11210 {
11211 IkReal j3eval[1];
11212 IkReal x860=((-1.0)*new_r00);
11213 CheckValue<IkReal> x862 = IKatan2WithCheck(IkReal(0),IkReal(x860),IKFAST_ATAN2_MAGTHRESH);
11214 if(!x862.valid){
11215 continue;
11216 }
11217 IkReal x861=((-1.0)*(x862.value));
11218 sj4=0;
11219 cj4=-1.0;
11220 j4=3.14159265358979;
11221 sj5=gconst7;
11222 cj5=gconst8;
11223 j5=x861;
11224 new_r01=0;
11225 new_r10=0;
11226 IkReal gconst6=x861;
11227 IkReal gconst7=0;
11228 IkReal x863 = new_r00*new_r00;
11229 if(IKabs(x863)==0){
11230 continue;
11231 }
11232 IkReal gconst8=(x860*(pow(x863,-0.5)));
11233 j3eval[0]=new_r11;
11234 if( IKabs(j3eval[0]) < 0.0000010000000000 )
11235 {
11236 {
11237 IkReal j3array[2], cj3array[2], sj3array[2];
11238 bool j3valid[2]={false};
11239 _nj3 = 2;
11240 CheckValue<IkReal> x864=IKPowWithIntegerCheck(gconst8,-1);
11241 if(!x864.valid){
11242 continue;
11243 }
11244 cj3array[0]=(new_r11*(x864.value));
11245 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
11246 {
11247  j3valid[0] = j3valid[1] = true;
11248  j3array[0] = IKacos(cj3array[0]);
11249  sj3array[0] = IKsin(j3array[0]);
11250  cj3array[1] = cj3array[0];
11251  j3array[1] = -j3array[0];
11252  sj3array[1] = -sj3array[0];
11253 }
11254 else if( isnan(cj3array[0]) )
11255 {
11256  // probably any value will work
11257  j3valid[0] = true;
11258  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
11259 }
11260 for(int ij3 = 0; ij3 < 2; ++ij3)
11261 {
11262 if( !j3valid[ij3] )
11263 {
11264  continue;
11265 }
11266 _ij3[0] = ij3; _ij3[1] = -1;
11267 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
11268 {
11269 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11270 {
11271  j3valid[iij3]=false; _ij3[1] = iij3; break;
11272 }
11273 }
11274 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11275 {
11276 IkReal evalcond[6];
11277 IkReal x865=IKsin(j3);
11278 IkReal x866=IKcos(j3);
11279 evalcond[0]=(new_r00*x865);
11280 evalcond[1]=(new_r11*x865);
11281 evalcond[2]=(gconst8*x865);
11282 evalcond[3]=(((new_r00*x866))+gconst8);
11283 evalcond[4]=(((gconst8*x866))+new_r00);
11284 evalcond[5]=(gconst8+(((-1.0)*new_r11*x866)));
11285 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
11286 {
11287 continue;
11288 }
11289 }
11290 
11291 {
11292 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11293 vinfos[0].jointtype = 1;
11294 vinfos[0].foffset = j0;
11295 vinfos[0].indices[0] = _ij0[0];
11296 vinfos[0].indices[1] = _ij0[1];
11297 vinfos[0].maxsolutions = _nj0;
11298 vinfos[1].jointtype = 1;
11299 vinfos[1].foffset = j1;
11300 vinfos[1].indices[0] = _ij1[0];
11301 vinfos[1].indices[1] = _ij1[1];
11302 vinfos[1].maxsolutions = _nj1;
11303 vinfos[2].jointtype = 1;
11304 vinfos[2].foffset = j2;
11305 vinfos[2].indices[0] = _ij2[0];
11306 vinfos[2].indices[1] = _ij2[1];
11307 vinfos[2].maxsolutions = _nj2;
11308 vinfos[3].jointtype = 1;
11309 vinfos[3].foffset = j3;
11310 vinfos[3].indices[0] = _ij3[0];
11311 vinfos[3].indices[1] = _ij3[1];
11312 vinfos[3].maxsolutions = _nj3;
11313 vinfos[4].jointtype = 1;
11314 vinfos[4].foffset = j4;
11315 vinfos[4].indices[0] = _ij4[0];
11316 vinfos[4].indices[1] = _ij4[1];
11317 vinfos[4].maxsolutions = _nj4;
11318 vinfos[5].jointtype = 1;
11319 vinfos[5].foffset = j5;
11320 vinfos[5].indices[0] = _ij5[0];
11321 vinfos[5].indices[1] = _ij5[1];
11322 vinfos[5].maxsolutions = _nj5;
11323 std::vector<int> vfree(0);
11324 solutions.AddSolution(vinfos,vfree);
11325 }
11326 }
11327 }
11328 
11329 } else
11330 {
11331 {
11332 IkReal j3array[2], cj3array[2], sj3array[2];
11333 bool j3valid[2]={false};
11334 _nj3 = 2;
11335 CheckValue<IkReal> x867=IKPowWithIntegerCheck(new_r11,-1);
11336 if(!x867.valid){
11337 continue;
11338 }
11339 cj3array[0]=(gconst8*(x867.value));
11340 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
11341 {
11342  j3valid[0] = j3valid[1] = true;
11343  j3array[0] = IKacos(cj3array[0]);
11344  sj3array[0] = IKsin(j3array[0]);
11345  cj3array[1] = cj3array[0];
11346  j3array[1] = -j3array[0];
11347  sj3array[1] = -sj3array[0];
11348 }
11349 else if( isnan(cj3array[0]) )
11350 {
11351  // probably any value will work
11352  j3valid[0] = true;
11353  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
11354 }
11355 for(int ij3 = 0; ij3 < 2; ++ij3)
11356 {
11357 if( !j3valid[ij3] )
11358 {
11359  continue;
11360 }
11361 _ij3[0] = ij3; _ij3[1] = -1;
11362 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
11363 {
11364 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11365 {
11366  j3valid[iij3]=false; _ij3[1] = iij3; break;
11367 }
11368 }
11369 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11370 {
11371 IkReal evalcond[6];
11372 IkReal x868=IKsin(j3);
11373 IkReal x869=IKcos(j3);
11374 IkReal x870=(gconst8*x869);
11375 evalcond[0]=(new_r00*x868);
11376 evalcond[1]=(new_r11*x868);
11377 evalcond[2]=(gconst8*x868);
11378 evalcond[3]=(((new_r00*x869))+gconst8);
11379 evalcond[4]=(new_r00+x870);
11380 evalcond[5]=((((-1.0)*x870))+new_r11);
11381 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
11382 {
11383 continue;
11384 }
11385 }
11386 
11387 {
11388 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11389 vinfos[0].jointtype = 1;
11390 vinfos[0].foffset = j0;
11391 vinfos[0].indices[0] = _ij0[0];
11392 vinfos[0].indices[1] = _ij0[1];
11393 vinfos[0].maxsolutions = _nj0;
11394 vinfos[1].jointtype = 1;
11395 vinfos[1].foffset = j1;
11396 vinfos[1].indices[0] = _ij1[0];
11397 vinfos[1].indices[1] = _ij1[1];
11398 vinfos[1].maxsolutions = _nj1;
11399 vinfos[2].jointtype = 1;
11400 vinfos[2].foffset = j2;
11401 vinfos[2].indices[0] = _ij2[0];
11402 vinfos[2].indices[1] = _ij2[1];
11403 vinfos[2].maxsolutions = _nj2;
11404 vinfos[3].jointtype = 1;
11405 vinfos[3].foffset = j3;
11406 vinfos[3].indices[0] = _ij3[0];
11407 vinfos[3].indices[1] = _ij3[1];
11408 vinfos[3].maxsolutions = _nj3;
11409 vinfos[4].jointtype = 1;
11410 vinfos[4].foffset = j4;
11411 vinfos[4].indices[0] = _ij4[0];
11412 vinfos[4].indices[1] = _ij4[1];
11413 vinfos[4].maxsolutions = _nj4;
11414 vinfos[5].jointtype = 1;
11415 vinfos[5].foffset = j5;
11416 vinfos[5].indices[0] = _ij5[0];
11417 vinfos[5].indices[1] = _ij5[1];
11418 vinfos[5].maxsolutions = _nj5;
11419 std::vector<int> vfree(0);
11420 solutions.AddSolution(vinfos,vfree);
11421 }
11422 }
11423 }
11424 
11425 }
11426 
11427 }
11428 
11429 }
11430 } while(0);
11431 if( bgotonextstatement )
11432 {
11433 bool bgotonextstatement = true;
11434 do
11435 {
11436 evalcond[0]=IKabs(new_r00);
11437 if( IKabs(evalcond[0]) < 0.0000050000000000 )
11438 {
11439 bgotonextstatement=false;
11440 {
11441 IkReal j3eval[1];
11442 CheckValue<IkReal> x872 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
11443 if(!x872.valid){
11444 continue;
11445 }
11446 IkReal x871=((-1.0)*(x872.value));
11447 sj4=0;
11448 cj4=-1.0;
11449 j4=3.14159265358979;
11450 sj5=gconst7;
11451 cj5=gconst8;
11452 j5=x871;
11453 new_r00=0;
11454 IkReal gconst6=x871;
11455 IkReal x873 = new_r10*new_r10;
11456 if(IKabs(x873)==0){
11457 continue;
11458 }
11459 IkReal gconst7=((-1.0)*new_r10*(pow(x873,-0.5)));
11460 IkReal gconst8=0;
11461 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
11462 if( IKabs(j3eval[0]) < 0.0000010000000000 )
11463 {
11464 {
11465 IkReal j3eval[1];
11466 CheckValue<IkReal> x875 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
11467 if(!x875.valid){
11468 continue;
11469 }
11470 IkReal x874=((-1.0)*(x875.value));
11471 sj4=0;
11472 cj4=-1.0;
11473 j4=3.14159265358979;
11474 sj5=gconst7;
11475 cj5=gconst8;
11476 j5=x874;
11477 new_r00=0;
11478 IkReal gconst6=x874;
11479 IkReal x876 = new_r10*new_r10;
11480 if(IKabs(x876)==0){
11481 continue;
11482 }
11483 IkReal gconst7=((-1.0)*new_r10*(pow(x876,-0.5)));
11484 IkReal gconst8=0;
11485 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
11486 if( IKabs(j3eval[0]) < 0.0000010000000000 )
11487 {
11488 {
11489 IkReal j3eval[1];
11490 CheckValue<IkReal> x878 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
11491 if(!x878.valid){
11492 continue;
11493 }
11494 IkReal x877=((-1.0)*(x878.value));
11495 sj4=0;
11496 cj4=-1.0;
11497 j4=3.14159265358979;
11498 sj5=gconst7;
11499 cj5=gconst8;
11500 j5=x877;
11501 new_r00=0;
11502 IkReal gconst6=x877;
11503 IkReal x879 = new_r10*new_r10;
11504 if(IKabs(x879)==0){
11505 continue;
11506 }
11507 IkReal gconst7=((-1.0)*new_r10*(pow(x879,-0.5)));
11508 IkReal gconst8=0;
11509 j3eval[0]=new_r10;
11510 if( IKabs(j3eval[0]) < 0.0000010000000000 )
11511 {
11512 continue; // 3 cases reached
11513 
11514 } else
11515 {
11516 {
11517 IkReal j3array[1], cj3array[1], sj3array[1];
11518 bool j3valid[1]={false};
11519 _nj3 = 1;
11520 CheckValue<IkReal> x880=IKPowWithIntegerCheck(gconst7,-1);
11521 if(!x880.valid){
11522 continue;
11523 }
11524 CheckValue<IkReal> x881=IKPowWithIntegerCheck(new_r10,-1);
11525 if(!x881.valid){
11526 continue;
11527 }
11528 if( IKabs((new_r11*(x880.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst7*(x881.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r11*(x880.value)))+IKsqr((gconst7*(x881.value)))-1) <= IKFAST_SINCOS_THRESH )
11529  continue;
11530 j3array[0]=IKatan2((new_r11*(x880.value)), (gconst7*(x881.value)));
11531 sj3array[0]=IKsin(j3array[0]);
11532 cj3array[0]=IKcos(j3array[0]);
11533 if( j3array[0] > IKPI )
11534 {
11535  j3array[0]-=IK2PI;
11536 }
11537 else if( j3array[0] < -IKPI )
11538 { j3array[0]+=IK2PI;
11539 }
11540 j3valid[0] = true;
11541 for(int ij3 = 0; ij3 < 1; ++ij3)
11542 {
11543 if( !j3valid[ij3] )
11544 {
11545  continue;
11546 }
11547 _ij3[0] = ij3; _ij3[1] = -1;
11548 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11549 {
11550 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11551 {
11552  j3valid[iij3]=false; _ij3[1] = iij3; break;
11553 }
11554 }
11555 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11556 {
11557 IkReal evalcond[8];
11558 IkReal x882=IKsin(j3);
11559 IkReal x883=IKcos(j3);
11560 IkReal x884=((1.0)*gconst7);
11561 IkReal x885=((1.0)*x883);
11562 IkReal x886=(x883*x884);
11563 evalcond[0]=(new_r10*x882);
11564 evalcond[1]=(gconst7*x882);
11565 evalcond[2]=((((-1.0)*new_r10*x885))+gconst7);
11566 evalcond[3]=((((-1.0)*x886))+new_r01);
11567 evalcond[4]=((((-1.0)*x882*x884))+new_r11);
11568 evalcond[5]=((((-1.0)*x886))+new_r10);
11569 evalcond[6]=(((new_r01*x882))+(((-1.0)*new_r11*x885)));
11570 evalcond[7]=(((new_r01*x883))+((new_r11*x882))+(((-1.0)*x884)));
11571 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
11572 {
11573 continue;
11574 }
11575 }
11576 
11577 {
11578 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11579 vinfos[0].jointtype = 1;
11580 vinfos[0].foffset = j0;
11581 vinfos[0].indices[0] = _ij0[0];
11582 vinfos[0].indices[1] = _ij0[1];
11583 vinfos[0].maxsolutions = _nj0;
11584 vinfos[1].jointtype = 1;
11585 vinfos[1].foffset = j1;
11586 vinfos[1].indices[0] = _ij1[0];
11587 vinfos[1].indices[1] = _ij1[1];
11588 vinfos[1].maxsolutions = _nj1;
11589 vinfos[2].jointtype = 1;
11590 vinfos[2].foffset = j2;
11591 vinfos[2].indices[0] = _ij2[0];
11592 vinfos[2].indices[1] = _ij2[1];
11593 vinfos[2].maxsolutions = _nj2;
11594 vinfos[3].jointtype = 1;
11595 vinfos[3].foffset = j3;
11596 vinfos[3].indices[0] = _ij3[0];
11597 vinfos[3].indices[1] = _ij3[1];
11598 vinfos[3].maxsolutions = _nj3;
11599 vinfos[4].jointtype = 1;
11600 vinfos[4].foffset = j4;
11601 vinfos[4].indices[0] = _ij4[0];
11602 vinfos[4].indices[1] = _ij4[1];
11603 vinfos[4].maxsolutions = _nj4;
11604 vinfos[5].jointtype = 1;
11605 vinfos[5].foffset = j5;
11606 vinfos[5].indices[0] = _ij5[0];
11607 vinfos[5].indices[1] = _ij5[1];
11608 vinfos[5].maxsolutions = _nj5;
11609 std::vector<int> vfree(0);
11610 solutions.AddSolution(vinfos,vfree);
11611 }
11612 }
11613 }
11614 
11615 }
11616 
11617 }
11618 
11619 } else
11620 {
11621 {
11622 IkReal j3array[1], cj3array[1], sj3array[1];
11623 bool j3valid[1]={false};
11624 _nj3 = 1;
11626 if(!x887.valid){
11627 continue;
11628 }
11629 CheckValue<IkReal> x888 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
11630 if(!x888.valid){
11631 continue;
11632 }
11633 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x887.value)))+(x888.value));
11634 sj3array[0]=IKsin(j3array[0]);
11635 cj3array[0]=IKcos(j3array[0]);
11636 if( j3array[0] > IKPI )
11637 {
11638  j3array[0]-=IK2PI;
11639 }
11640 else if( j3array[0] < -IKPI )
11641 { j3array[0]+=IK2PI;
11642 }
11643 j3valid[0] = true;
11644 for(int ij3 = 0; ij3 < 1; ++ij3)
11645 {
11646 if( !j3valid[ij3] )
11647 {
11648  continue;
11649 }
11650 _ij3[0] = ij3; _ij3[1] = -1;
11651 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11652 {
11653 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11654 {
11655  j3valid[iij3]=false; _ij3[1] = iij3; break;
11656 }
11657 }
11658 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11659 {
11660 IkReal evalcond[8];
11661 IkReal x889=IKsin(j3);
11662 IkReal x890=IKcos(j3);
11663 IkReal x891=((1.0)*gconst7);
11664 IkReal x892=((1.0)*x890);
11665 IkReal x893=(x890*x891);
11666 evalcond[0]=(new_r10*x889);
11667 evalcond[1]=(gconst7*x889);
11668 evalcond[2]=(gconst7+(((-1.0)*new_r10*x892)));
11669 evalcond[3]=((((-1.0)*x893))+new_r01);
11670 evalcond[4]=((((-1.0)*x889*x891))+new_r11);
11671 evalcond[5]=((((-1.0)*x893))+new_r10);
11672 evalcond[6]=(((new_r01*x889))+(((-1.0)*new_r11*x892)));
11673 evalcond[7]=(((new_r11*x889))+((new_r01*x890))+(((-1.0)*x891)));
11674 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
11675 {
11676 continue;
11677 }
11678 }
11679 
11680 {
11681 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11682 vinfos[0].jointtype = 1;
11683 vinfos[0].foffset = j0;
11684 vinfos[0].indices[0] = _ij0[0];
11685 vinfos[0].indices[1] = _ij0[1];
11686 vinfos[0].maxsolutions = _nj0;
11687 vinfos[1].jointtype = 1;
11688 vinfos[1].foffset = j1;
11689 vinfos[1].indices[0] = _ij1[0];
11690 vinfos[1].indices[1] = _ij1[1];
11691 vinfos[1].maxsolutions = _nj1;
11692 vinfos[2].jointtype = 1;
11693 vinfos[2].foffset = j2;
11694 vinfos[2].indices[0] = _ij2[0];
11695 vinfos[2].indices[1] = _ij2[1];
11696 vinfos[2].maxsolutions = _nj2;
11697 vinfos[3].jointtype = 1;
11698 vinfos[3].foffset = j3;
11699 vinfos[3].indices[0] = _ij3[0];
11700 vinfos[3].indices[1] = _ij3[1];
11701 vinfos[3].maxsolutions = _nj3;
11702 vinfos[4].jointtype = 1;
11703 vinfos[4].foffset = j4;
11704 vinfos[4].indices[0] = _ij4[0];
11705 vinfos[4].indices[1] = _ij4[1];
11706 vinfos[4].maxsolutions = _nj4;
11707 vinfos[5].jointtype = 1;
11708 vinfos[5].foffset = j5;
11709 vinfos[5].indices[0] = _ij5[0];
11710 vinfos[5].indices[1] = _ij5[1];
11711 vinfos[5].maxsolutions = _nj5;
11712 std::vector<int> vfree(0);
11713 solutions.AddSolution(vinfos,vfree);
11714 }
11715 }
11716 }
11717 
11718 }
11719 
11720 }
11721 
11722 } else
11723 {
11724 {
11725 IkReal j3array[1], cj3array[1], sj3array[1];
11726 bool j3valid[1]={false};
11727 _nj3 = 1;
11729 if(!x894.valid){
11730 continue;
11731 }
11732 CheckValue<IkReal> x895 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
11733 if(!x895.valid){
11734 continue;
11735 }
11736 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x894.value)))+(x895.value));
11737 sj3array[0]=IKsin(j3array[0]);
11738 cj3array[0]=IKcos(j3array[0]);
11739 if( j3array[0] > IKPI )
11740 {
11741  j3array[0]-=IK2PI;
11742 }
11743 else if( j3array[0] < -IKPI )
11744 { j3array[0]+=IK2PI;
11745 }
11746 j3valid[0] = true;
11747 for(int ij3 = 0; ij3 < 1; ++ij3)
11748 {
11749 if( !j3valid[ij3] )
11750 {
11751  continue;
11752 }
11753 _ij3[0] = ij3; _ij3[1] = -1;
11754 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11755 {
11756 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11757 {
11758  j3valid[iij3]=false; _ij3[1] = iij3; break;
11759 }
11760 }
11761 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11762 {
11763 IkReal evalcond[8];
11764 IkReal x896=IKsin(j3);
11765 IkReal x897=IKcos(j3);
11766 IkReal x898=((1.0)*gconst7);
11767 IkReal x899=((1.0)*x897);
11768 IkReal x900=(x897*x898);
11769 evalcond[0]=(new_r10*x896);
11770 evalcond[1]=(gconst7*x896);
11771 evalcond[2]=(gconst7+(((-1.0)*new_r10*x899)));
11772 evalcond[3]=((((-1.0)*x900))+new_r01);
11773 evalcond[4]=((((-1.0)*x896*x898))+new_r11);
11774 evalcond[5]=((((-1.0)*x900))+new_r10);
11775 evalcond[6]=(((new_r01*x896))+(((-1.0)*new_r11*x899)));
11776 evalcond[7]=(((new_r11*x896))+((new_r01*x897))+(((-1.0)*x898)));
11777 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
11778 {
11779 continue;
11780 }
11781 }
11782 
11783 {
11784 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11785 vinfos[0].jointtype = 1;
11786 vinfos[0].foffset = j0;
11787 vinfos[0].indices[0] = _ij0[0];
11788 vinfos[0].indices[1] = _ij0[1];
11789 vinfos[0].maxsolutions = _nj0;
11790 vinfos[1].jointtype = 1;
11791 vinfos[1].foffset = j1;
11792 vinfos[1].indices[0] = _ij1[0];
11793 vinfos[1].indices[1] = _ij1[1];
11794 vinfos[1].maxsolutions = _nj1;
11795 vinfos[2].jointtype = 1;
11796 vinfos[2].foffset = j2;
11797 vinfos[2].indices[0] = _ij2[0];
11798 vinfos[2].indices[1] = _ij2[1];
11799 vinfos[2].maxsolutions = _nj2;
11800 vinfos[3].jointtype = 1;
11801 vinfos[3].foffset = j3;
11802 vinfos[3].indices[0] = _ij3[0];
11803 vinfos[3].indices[1] = _ij3[1];
11804 vinfos[3].maxsolutions = _nj3;
11805 vinfos[4].jointtype = 1;
11806 vinfos[4].foffset = j4;
11807 vinfos[4].indices[0] = _ij4[0];
11808 vinfos[4].indices[1] = _ij4[1];
11809 vinfos[4].maxsolutions = _nj4;
11810 vinfos[5].jointtype = 1;
11811 vinfos[5].foffset = j5;
11812 vinfos[5].indices[0] = _ij5[0];
11813 vinfos[5].indices[1] = _ij5[1];
11814 vinfos[5].maxsolutions = _nj5;
11815 std::vector<int> vfree(0);
11816 solutions.AddSolution(vinfos,vfree);
11817 }
11818 }
11819 }
11820 
11821 }
11822 
11823 }
11824 
11825 }
11826 } while(0);
11827 if( bgotonextstatement )
11828 {
11829 bool bgotonextstatement = true;
11830 do
11831 {
11832 if( 1 )
11833 {
11834 bgotonextstatement=false;
11835 continue; // branch miss [j3]
11836 
11837 }
11838 } while(0);
11839 if( bgotonextstatement )
11840 {
11841 }
11842 }
11843 }
11844 }
11845 }
11846 }
11847 
11848 } else
11849 {
11850 {
11851 IkReal j3array[1], cj3array[1], sj3array[1];
11852 bool j3valid[1]={false};
11853 _nj3 = 1;
11854 CheckValue<IkReal> x901=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst7*new_r10))+(((-1.0)*gconst8*new_r00)))),-1);
11855 if(!x901.valid){
11856 continue;
11857 }
11858 CheckValue<IkReal> x902 = IKatan2WithCheck(IkReal((((new_r00*new_r10))+((gconst7*gconst8)))),IkReal(((gconst8*gconst8)+(((-1.0)*(new_r10*new_r10))))),IKFAST_ATAN2_MAGTHRESH);
11859 if(!x902.valid){
11860 continue;
11861 }
11862 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x901.value)))+(x902.value));
11863 sj3array[0]=IKsin(j3array[0]);
11864 cj3array[0]=IKcos(j3array[0]);
11865 if( j3array[0] > IKPI )
11866 {
11867  j3array[0]-=IK2PI;
11868 }
11869 else if( j3array[0] < -IKPI )
11870 { j3array[0]+=IK2PI;
11871 }
11872 j3valid[0] = true;
11873 for(int ij3 = 0; ij3 < 1; ++ij3)
11874 {
11875 if( !j3valid[ij3] )
11876 {
11877  continue;
11878 }
11879 _ij3[0] = ij3; _ij3[1] = -1;
11880 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11881 {
11882 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11883 {
11884  j3valid[iij3]=false; _ij3[1] = iij3; break;
11885 }
11886 }
11887 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11888 {
11889 IkReal evalcond[8];
11890 IkReal x903=IKcos(j3);
11891 IkReal x904=IKsin(j3);
11892 IkReal x905=(gconst8*x904);
11893 IkReal x906=(gconst7*x904);
11894 IkReal x907=((1.0)*x903);
11895 IkReal x908=(gconst7*x907);
11896 evalcond[0]=(gconst8+((new_r10*x904))+((new_r00*x903)));
11897 evalcond[1]=(new_r00+((gconst8*x903))+x906);
11898 evalcond[2]=(gconst7+((new_r00*x904))+(((-1.0)*new_r10*x907)));
11899 evalcond[3]=((((-1.0)*new_r11*x907))+gconst8+((new_r01*x904)));
11900 evalcond[4]=((((-1.0)*x908))+new_r01+x905);
11901 evalcond[5]=((((-1.0)*x908))+new_r10+x905);
11902 evalcond[6]=((((-1.0)*gconst7))+((new_r11*x904))+((new_r01*x903)));
11903 evalcond[7]=((((-1.0)*gconst8*x907))+(((-1.0)*x906))+new_r11);
11904 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
11905 {
11906 continue;
11907 }
11908 }
11909 
11910 {
11911 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11912 vinfos[0].jointtype = 1;
11913 vinfos[0].foffset = j0;
11914 vinfos[0].indices[0] = _ij0[0];
11915 vinfos[0].indices[1] = _ij0[1];
11916 vinfos[0].maxsolutions = _nj0;
11917 vinfos[1].jointtype = 1;
11918 vinfos[1].foffset = j1;
11919 vinfos[1].indices[0] = _ij1[0];
11920 vinfos[1].indices[1] = _ij1[1];
11921 vinfos[1].maxsolutions = _nj1;
11922 vinfos[2].jointtype = 1;
11923 vinfos[2].foffset = j2;
11924 vinfos[2].indices[0] = _ij2[0];
11925 vinfos[2].indices[1] = _ij2[1];
11926 vinfos[2].maxsolutions = _nj2;
11927 vinfos[3].jointtype = 1;
11928 vinfos[3].foffset = j3;
11929 vinfos[3].indices[0] = _ij3[0];
11930 vinfos[3].indices[1] = _ij3[1];
11931 vinfos[3].maxsolutions = _nj3;
11932 vinfos[4].jointtype = 1;
11933 vinfos[4].foffset = j4;
11934 vinfos[4].indices[0] = _ij4[0];
11935 vinfos[4].indices[1] = _ij4[1];
11936 vinfos[4].maxsolutions = _nj4;
11937 vinfos[5].jointtype = 1;
11938 vinfos[5].foffset = j5;
11939 vinfos[5].indices[0] = _ij5[0];
11940 vinfos[5].indices[1] = _ij5[1];
11941 vinfos[5].maxsolutions = _nj5;
11942 std::vector<int> vfree(0);
11943 solutions.AddSolution(vinfos,vfree);
11944 }
11945 }
11946 }
11947 
11948 }
11949 
11950 }
11951 
11952 } else
11953 {
11954 {
11955 IkReal j3array[1], cj3array[1], sj3array[1];
11956 bool j3valid[1]={false};
11957 _nj3 = 1;
11958 IkReal x909=((1.0)*new_r10);
11959 CheckValue<IkReal> x910=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst7*x909))+(((-1.0)*gconst8*new_r00)))),-1);
11960 if(!x910.valid){
11961 continue;
11962 }
11963 CheckValue<IkReal> x911 = IKatan2WithCheck(IkReal((((new_r00*new_r01))+((gconst7*gconst8)))),IkReal(((gconst8*gconst8)+(((-1.0)*new_r01*x909)))),IKFAST_ATAN2_MAGTHRESH);
11964 if(!x911.valid){
11965 continue;
11966 }
11967 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x910.value)))+(x911.value));
11968 sj3array[0]=IKsin(j3array[0]);
11969 cj3array[0]=IKcos(j3array[0]);
11970 if( j3array[0] > IKPI )
11971 {
11972  j3array[0]-=IK2PI;
11973 }
11974 else if( j3array[0] < -IKPI )
11975 { j3array[0]+=IK2PI;
11976 }
11977 j3valid[0] = true;
11978 for(int ij3 = 0; ij3 < 1; ++ij3)
11979 {
11980 if( !j3valid[ij3] )
11981 {
11982  continue;
11983 }
11984 _ij3[0] = ij3; _ij3[1] = -1;
11985 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11986 {
11987 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11988 {
11989  j3valid[iij3]=false; _ij3[1] = iij3; break;
11990 }
11991 }
11992 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11993 {
11994 IkReal evalcond[8];
11995 IkReal x912=IKcos(j3);
11996 IkReal x913=IKsin(j3);
11997 IkReal x914=(gconst8*x913);
11998 IkReal x915=(gconst7*x913);
11999 IkReal x916=((1.0)*x912);
12000 IkReal x917=(gconst7*x916);
12001 evalcond[0]=(gconst8+((new_r10*x913))+((new_r00*x912)));
12002 evalcond[1]=(((gconst8*x912))+new_r00+x915);
12003 evalcond[2]=(gconst7+((new_r00*x913))+(((-1.0)*new_r10*x916)));
12004 evalcond[3]=(gconst8+((new_r01*x913))+(((-1.0)*new_r11*x916)));
12005 evalcond[4]=((((-1.0)*x917))+new_r01+x914);
12006 evalcond[5]=((((-1.0)*x917))+new_r10+x914);
12007 evalcond[6]=(((new_r11*x913))+(((-1.0)*gconst7))+((new_r01*x912)));
12008 evalcond[7]=((((-1.0)*gconst8*x916))+(((-1.0)*x915))+new_r11);
12009 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
12010 {
12011 continue;
12012 }
12013 }
12014 
12015 {
12016 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12017 vinfos[0].jointtype = 1;
12018 vinfos[0].foffset = j0;
12019 vinfos[0].indices[0] = _ij0[0];
12020 vinfos[0].indices[1] = _ij0[1];
12021 vinfos[0].maxsolutions = _nj0;
12022 vinfos[1].jointtype = 1;
12023 vinfos[1].foffset = j1;
12024 vinfos[1].indices[0] = _ij1[0];
12025 vinfos[1].indices[1] = _ij1[1];
12026 vinfos[1].maxsolutions = _nj1;
12027 vinfos[2].jointtype = 1;
12028 vinfos[2].foffset = j2;
12029 vinfos[2].indices[0] = _ij2[0];
12030 vinfos[2].indices[1] = _ij2[1];
12031 vinfos[2].maxsolutions = _nj2;
12032 vinfos[3].jointtype = 1;
12033 vinfos[3].foffset = j3;
12034 vinfos[3].indices[0] = _ij3[0];
12035 vinfos[3].indices[1] = _ij3[1];
12036 vinfos[3].maxsolutions = _nj3;
12037 vinfos[4].jointtype = 1;
12038 vinfos[4].foffset = j4;
12039 vinfos[4].indices[0] = _ij4[0];
12040 vinfos[4].indices[1] = _ij4[1];
12041 vinfos[4].maxsolutions = _nj4;
12042 vinfos[5].jointtype = 1;
12043 vinfos[5].foffset = j5;
12044 vinfos[5].indices[0] = _ij5[0];
12045 vinfos[5].indices[1] = _ij5[1];
12046 vinfos[5].maxsolutions = _nj5;
12047 std::vector<int> vfree(0);
12048 solutions.AddSolution(vinfos,vfree);
12049 }
12050 }
12051 }
12052 
12053 }
12054 
12055 }
12056 
12057 } else
12058 {
12059 {
12060 IkReal j3array[1], cj3array[1], sj3array[1];
12061 bool j3valid[1]={false};
12062 _nj3 = 1;
12063 IkReal x918=((1.0)*new_r10);
12064 CheckValue<IkReal> x919 = IKatan2WithCheck(IkReal((((gconst8*new_r11))+((gconst8*new_r00)))),IkReal((((gconst8*new_r01))+(((-1.0)*gconst8*x918)))),IKFAST_ATAN2_MAGTHRESH);
12065 if(!x919.valid){
12066 continue;
12067 }
12068 CheckValue<IkReal> x920=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*new_r01))+(((-1.0)*new_r11*x918)))),-1);
12069 if(!x920.valid){
12070 continue;
12071 }
12072 j3array[0]=((-1.5707963267949)+(x919.value)+(((1.5707963267949)*(x920.value))));
12073 sj3array[0]=IKsin(j3array[0]);
12074 cj3array[0]=IKcos(j3array[0]);
12075 if( j3array[0] > IKPI )
12076 {
12077  j3array[0]-=IK2PI;
12078 }
12079 else if( j3array[0] < -IKPI )
12080 { j3array[0]+=IK2PI;
12081 }
12082 j3valid[0] = true;
12083 for(int ij3 = 0; ij3 < 1; ++ij3)
12084 {
12085 if( !j3valid[ij3] )
12086 {
12087  continue;
12088 }
12089 _ij3[0] = ij3; _ij3[1] = -1;
12090 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12091 {
12092 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12093 {
12094  j3valid[iij3]=false; _ij3[1] = iij3; break;
12095 }
12096 }
12097 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12098 {
12099 IkReal evalcond[8];
12100 IkReal x921=IKcos(j3);
12101 IkReal x922=IKsin(j3);
12102 IkReal x923=(gconst8*x922);
12103 IkReal x924=(gconst7*x922);
12104 IkReal x925=((1.0)*x921);
12105 IkReal x926=(gconst7*x925);
12106 evalcond[0]=(gconst8+((new_r00*x921))+((new_r10*x922)));
12107 evalcond[1]=(((gconst8*x921))+new_r00+x924);
12108 evalcond[2]=(gconst7+(((-1.0)*new_r10*x925))+((new_r00*x922)));
12109 evalcond[3]=((((-1.0)*new_r11*x925))+gconst8+((new_r01*x922)));
12110 evalcond[4]=((((-1.0)*x926))+new_r01+x923);
12111 evalcond[5]=((((-1.0)*x926))+new_r10+x923);
12112 evalcond[6]=((((-1.0)*gconst7))+((new_r01*x921))+((new_r11*x922)));
12113 evalcond[7]=((((-1.0)*gconst8*x925))+(((-1.0)*x924))+new_r11);
12114 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
12115 {
12116 continue;
12117 }
12118 }
12119 
12120 {
12121 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12122 vinfos[0].jointtype = 1;
12123 vinfos[0].foffset = j0;
12124 vinfos[0].indices[0] = _ij0[0];
12125 vinfos[0].indices[1] = _ij0[1];
12126 vinfos[0].maxsolutions = _nj0;
12127 vinfos[1].jointtype = 1;
12128 vinfos[1].foffset = j1;
12129 vinfos[1].indices[0] = _ij1[0];
12130 vinfos[1].indices[1] = _ij1[1];
12131 vinfos[1].maxsolutions = _nj1;
12132 vinfos[2].jointtype = 1;
12133 vinfos[2].foffset = j2;
12134 vinfos[2].indices[0] = _ij2[0];
12135 vinfos[2].indices[1] = _ij2[1];
12136 vinfos[2].maxsolutions = _nj2;
12137 vinfos[3].jointtype = 1;
12138 vinfos[3].foffset = j3;
12139 vinfos[3].indices[0] = _ij3[0];
12140 vinfos[3].indices[1] = _ij3[1];
12141 vinfos[3].maxsolutions = _nj3;
12142 vinfos[4].jointtype = 1;
12143 vinfos[4].foffset = j4;
12144 vinfos[4].indices[0] = _ij4[0];
12145 vinfos[4].indices[1] = _ij4[1];
12146 vinfos[4].maxsolutions = _nj4;
12147 vinfos[5].jointtype = 1;
12148 vinfos[5].foffset = j5;
12149 vinfos[5].indices[0] = _ij5[0];
12150 vinfos[5].indices[1] = _ij5[1];
12151 vinfos[5].maxsolutions = _nj5;
12152 std::vector<int> vfree(0);
12153 solutions.AddSolution(vinfos,vfree);
12154 }
12155 }
12156 }
12157 
12158 }
12159 
12160 }
12161 
12162 }
12163 } while(0);
12164 if( bgotonextstatement )
12165 {
12166 bool bgotonextstatement = true;
12167 do
12168 {
12169 IkReal x929 = ((new_r10*new_r10)+(new_r00*new_r00));
12170 if(IKabs(x929)==0){
12171 continue;
12172 }
12173 IkReal x927=pow(x929,-0.5);
12174 IkReal x928=((1.0)*x927);
12175 CheckValue<IkReal> x930 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12176 if(!x930.valid){
12177 continue;
12178 }
12179 IkReal gconst9=((3.14159265358979)+(((-1.0)*(x930.value))));
12180 IkReal gconst10=(new_r10*x928);
12181 IkReal gconst11=(new_r00*x928);
12182 CheckValue<IkReal> x931 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12183 if(!x931.valid){
12184 continue;
12185 }
12186 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j5+(x931.value))))), 6.28318530717959)));
12187 if( IKabs(evalcond[0]) < 0.0000050000000000 )
12188 {
12189 bgotonextstatement=false;
12190 {
12191 IkReal j3eval[3];
12192 CheckValue<IkReal> x935 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12193 if(!x935.valid){
12194 continue;
12195 }
12196 IkReal x932=((1.0)*(x935.value));
12197 IkReal x933=x927;
12198 IkReal x934=((1.0)*x933);
12199 sj4=0;
12200 cj4=-1.0;
12201 j4=3.14159265358979;
12202 sj5=gconst10;
12203 cj5=gconst11;
12204 j5=((3.14159265)+(((-1.0)*x932)));
12205 IkReal gconst9=((3.14159265358979)+(((-1.0)*x932)));
12206 IkReal gconst10=(new_r10*x934);
12207 IkReal gconst11=(new_r00*x934);
12208 IkReal x936=new_r00*new_r00;
12209 IkReal x937=((1.0)*new_r00);
12210 IkReal x938=((((-1.0)*new_r01*x937))+(((-1.0)*new_r10*new_r11)));
12211 IkReal x939=x927;
12212 IkReal x940=(new_r00*x939);
12213 j3eval[0]=x938;
12214 j3eval[1]=((IKabs((((new_r01*x940))+(((-1.0)*new_r10*x937*x939)))))+(IKabs((((x936*x939))+((new_r11*x940))))));
12215 j3eval[2]=IKsign(x938);
12216 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
12217 {
12218 {
12219 IkReal j3eval[1];
12220 CheckValue<IkReal> x944 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12221 if(!x944.valid){
12222 continue;
12223 }
12224 IkReal x941=((1.0)*(x944.value));
12225 IkReal x942=x927;
12226 IkReal x943=((1.0)*x942);
12227 sj4=0;
12228 cj4=-1.0;
12229 j4=3.14159265358979;
12230 sj5=gconst10;
12231 cj5=gconst11;
12232 j5=((3.14159265)+(((-1.0)*x941)));
12233 IkReal gconst9=((3.14159265358979)+(((-1.0)*x941)));
12234 IkReal gconst10=(new_r10*x943);
12235 IkReal gconst11=(new_r00*x943);
12236 IkReal x945=new_r10*new_r10;
12237 IkReal x946=new_r00*new_r00;
12238 IkReal x947=((1.0)*new_r01);
12239 CheckValue<IkReal> x951=IKPowWithIntegerCheck((x945+x946),-1);
12240 if(!x951.valid){
12241 continue;
12242 }
12243 IkReal x948=x951.value;
12244 IkReal x949=(new_r10*x948);
12245 IkReal x950=(new_r01*x948);
12246 j3eval[0]=((IKabs((((new_r00*x949))+((new_r00*x945*x950))+((x950*(new_r00*new_r00*new_r00))))))+(IKabs((((x946*x948))+(((-1.0)*x947*x949*(new_r10*new_r10)))+(((-1.0)*x946*x947*x949))))));
12247 if( IKabs(j3eval[0]) < 0.0000010000000000 )
12248 {
12249 {
12250 IkReal j3eval[1];
12251 CheckValue<IkReal> x955 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12252 if(!x955.valid){
12253 continue;
12254 }
12255 IkReal x952=((1.0)*(x955.value));
12256 IkReal x953=x927;
12257 IkReal x954=((1.0)*x953);
12258 sj4=0;
12259 cj4=-1.0;
12260 j4=3.14159265358979;
12261 sj5=gconst10;
12262 cj5=gconst11;
12263 j5=((3.14159265)+(((-1.0)*x952)));
12264 IkReal gconst9=((3.14159265358979)+(((-1.0)*x952)));
12265 IkReal gconst10=(new_r10*x954);
12266 IkReal gconst11=(new_r00*x954);
12267 IkReal x956=new_r00*new_r00;
12268 IkReal x957=new_r10*new_r10;
12269 CheckValue<IkReal> x961=IKPowWithIntegerCheck((x957+x956),-1);
12270 if(!x961.valid){
12271 continue;
12272 }
12273 IkReal x958=x961.value;
12274 IkReal x959=(new_r10*x958);
12275 IkReal x960=((1.0)*x958);
12276 j3eval[0]=((IKabs(((((-1.0)*x956*x957*x960))+((x956*x958))+(((-1.0)*x960*(x957*x957))))))+(IKabs((((new_r00*x959))+((x959*(new_r00*new_r00*new_r00)))+((new_r00*x959*(new_r10*new_r10)))))));
12277 if( IKabs(j3eval[0]) < 0.0000010000000000 )
12278 {
12279 {
12280 IkReal evalcond[2];
12281 bool bgotonextstatement = true;
12282 do
12283 {
12284 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
12285 if( IKabs(evalcond[0]) < 0.0000050000000000 )
12286 {
12287 bgotonextstatement=false;
12288 {
12289 IkReal j3eval[1];
12290 CheckValue<IkReal> x963 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
12291 if(!x963.valid){
12292 continue;
12293 }
12294 IkReal x962=((1.0)*(x963.value));
12295 sj4=0;
12296 cj4=-1.0;
12297 j4=3.14159265358979;
12298 sj5=gconst10;
12299 cj5=gconst11;
12300 j5=((3.14159265)+(((-1.0)*x962)));
12301 new_r11=0;
12302 new_r00=0;
12303 IkReal gconst9=((3.14159265358979)+(((-1.0)*x962)));
12304 IkReal x964 = new_r10*new_r10;
12305 if(IKabs(x964)==0){
12306 continue;
12307 }
12308 IkReal gconst10=((1.0)*new_r10*(pow(x964,-0.5)));
12309 IkReal gconst11=0;
12310 j3eval[0]=new_r10;
12311 if( IKabs(j3eval[0]) < 0.0000010000000000 )
12312 {
12313 {
12314 IkReal j3array[2], cj3array[2], sj3array[2];
12315 bool j3valid[2]={false};
12316 _nj3 = 2;
12317 CheckValue<IkReal> x965=IKPowWithIntegerCheck(gconst10,-1);
12318 if(!x965.valid){
12319 continue;
12320 }
12321 cj3array[0]=(new_r01*(x965.value));
12322 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
12323 {
12324  j3valid[0] = j3valid[1] = true;
12325  j3array[0] = IKacos(cj3array[0]);
12326  sj3array[0] = IKsin(j3array[0]);
12327  cj3array[1] = cj3array[0];
12328  j3array[1] = -j3array[0];
12329  sj3array[1] = -sj3array[0];
12330 }
12331 else if( isnan(cj3array[0]) )
12332 {
12333  // probably any value will work
12334  j3valid[0] = true;
12335  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
12336 }
12337 for(int ij3 = 0; ij3 < 2; ++ij3)
12338 {
12339 if( !j3valid[ij3] )
12340 {
12341  continue;
12342 }
12343 _ij3[0] = ij3; _ij3[1] = -1;
12344 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
12345 {
12346 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12347 {
12348  j3valid[iij3]=false; _ij3[1] = iij3; break;
12349 }
12350 }
12351 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12352 {
12353 IkReal evalcond[6];
12354 IkReal x966=IKsin(j3);
12355 IkReal x967=IKcos(j3);
12356 IkReal x968=((1.0)*gconst10);
12357 evalcond[0]=(new_r01*x966);
12358 evalcond[1]=(new_r10*x966);
12359 evalcond[2]=(gconst10*x966);
12360 evalcond[3]=(gconst10+(((-1.0)*new_r10*x967)));
12361 evalcond[4]=((((-1.0)*x967*x968))+new_r10);
12362 evalcond[5]=(((new_r01*x967))+(((-1.0)*x968)));
12363 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
12364 {
12365 continue;
12366 }
12367 }
12368 
12369 {
12370 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12371 vinfos[0].jointtype = 1;
12372 vinfos[0].foffset = j0;
12373 vinfos[0].indices[0] = _ij0[0];
12374 vinfos[0].indices[1] = _ij0[1];
12375 vinfos[0].maxsolutions = _nj0;
12376 vinfos[1].jointtype = 1;
12377 vinfos[1].foffset = j1;
12378 vinfos[1].indices[0] = _ij1[0];
12379 vinfos[1].indices[1] = _ij1[1];
12380 vinfos[1].maxsolutions = _nj1;
12381 vinfos[2].jointtype = 1;
12382 vinfos[2].foffset = j2;
12383 vinfos[2].indices[0] = _ij2[0];
12384 vinfos[2].indices[1] = _ij2[1];
12385 vinfos[2].maxsolutions = _nj2;
12386 vinfos[3].jointtype = 1;
12387 vinfos[3].foffset = j3;
12388 vinfos[3].indices[0] = _ij3[0];
12389 vinfos[3].indices[1] = _ij3[1];
12390 vinfos[3].maxsolutions = _nj3;
12391 vinfos[4].jointtype = 1;
12392 vinfos[4].foffset = j4;
12393 vinfos[4].indices[0] = _ij4[0];
12394 vinfos[4].indices[1] = _ij4[1];
12395 vinfos[4].maxsolutions = _nj4;
12396 vinfos[5].jointtype = 1;
12397 vinfos[5].foffset = j5;
12398 vinfos[5].indices[0] = _ij5[0];
12399 vinfos[5].indices[1] = _ij5[1];
12400 vinfos[5].maxsolutions = _nj5;
12401 std::vector<int> vfree(0);
12402 solutions.AddSolution(vinfos,vfree);
12403 }
12404 }
12405 }
12406 
12407 } else
12408 {
12409 {
12410 IkReal j3array[2], cj3array[2], sj3array[2];
12411 bool j3valid[2]={false};
12412 _nj3 = 2;
12413 CheckValue<IkReal> x969=IKPowWithIntegerCheck(new_r10,-1);
12414 if(!x969.valid){
12415 continue;
12416 }
12417 cj3array[0]=(gconst10*(x969.value));
12418 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
12419 {
12420  j3valid[0] = j3valid[1] = true;
12421  j3array[0] = IKacos(cj3array[0]);
12422  sj3array[0] = IKsin(j3array[0]);
12423  cj3array[1] = cj3array[0];
12424  j3array[1] = -j3array[0];
12425  sj3array[1] = -sj3array[0];
12426 }
12427 else if( isnan(cj3array[0]) )
12428 {
12429  // probably any value will work
12430  j3valid[0] = true;
12431  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
12432 }
12433 for(int ij3 = 0; ij3 < 2; ++ij3)
12434 {
12435 if( !j3valid[ij3] )
12436 {
12437  continue;
12438 }
12439 _ij3[0] = ij3; _ij3[1] = -1;
12440 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
12441 {
12442 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12443 {
12444  j3valid[iij3]=false; _ij3[1] = iij3; break;
12445 }
12446 }
12447 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12448 {
12449 IkReal evalcond[6];
12450 IkReal x970=IKsin(j3);
12451 IkReal x971=IKcos(j3);
12452 IkReal x972=((1.0)*gconst10);
12453 IkReal x973=(x971*x972);
12454 evalcond[0]=(new_r01*x970);
12455 evalcond[1]=(new_r10*x970);
12456 evalcond[2]=(gconst10*x970);
12457 evalcond[3]=(new_r01+(((-1.0)*x973)));
12458 evalcond[4]=(new_r10+(((-1.0)*x973)));
12459 evalcond[5]=(((new_r01*x971))+(((-1.0)*x972)));
12460 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
12461 {
12462 continue;
12463 }
12464 }
12465 
12466 {
12467 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12468 vinfos[0].jointtype = 1;
12469 vinfos[0].foffset = j0;
12470 vinfos[0].indices[0] = _ij0[0];
12471 vinfos[0].indices[1] = _ij0[1];
12472 vinfos[0].maxsolutions = _nj0;
12473 vinfos[1].jointtype = 1;
12474 vinfos[1].foffset = j1;
12475 vinfos[1].indices[0] = _ij1[0];
12476 vinfos[1].indices[1] = _ij1[1];
12477 vinfos[1].maxsolutions = _nj1;
12478 vinfos[2].jointtype = 1;
12479 vinfos[2].foffset = j2;
12480 vinfos[2].indices[0] = _ij2[0];
12481 vinfos[2].indices[1] = _ij2[1];
12482 vinfos[2].maxsolutions = _nj2;
12483 vinfos[3].jointtype = 1;
12484 vinfos[3].foffset = j3;
12485 vinfos[3].indices[0] = _ij3[0];
12486 vinfos[3].indices[1] = _ij3[1];
12487 vinfos[3].maxsolutions = _nj3;
12488 vinfos[4].jointtype = 1;
12489 vinfos[4].foffset = j4;
12490 vinfos[4].indices[0] = _ij4[0];
12491 vinfos[4].indices[1] = _ij4[1];
12492 vinfos[4].maxsolutions = _nj4;
12493 vinfos[5].jointtype = 1;
12494 vinfos[5].foffset = j5;
12495 vinfos[5].indices[0] = _ij5[0];
12496 vinfos[5].indices[1] = _ij5[1];
12497 vinfos[5].maxsolutions = _nj5;
12498 std::vector<int> vfree(0);
12499 solutions.AddSolution(vinfos,vfree);
12500 }
12501 }
12502 }
12503 
12504 }
12505 
12506 }
12507 
12508 }
12509 } while(0);
12510 if( bgotonextstatement )
12511 {
12512 bool bgotonextstatement = true;
12513 do
12514 {
12515 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
12516 evalcond[1]=gconst11;
12517 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
12518 {
12519 bgotonextstatement=false;
12520 {
12521 IkReal j3eval[3];
12522 CheckValue<IkReal> x975 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12523 if(!x975.valid){
12524 continue;
12525 }
12526 IkReal x974=((1.0)*(x975.value));
12527 sj4=0;
12528 cj4=-1.0;
12529 j4=3.14159265358979;
12530 sj5=gconst10;
12531 cj5=gconst11;
12532 j5=((3.14159265)+(((-1.0)*x974)));
12533 new_r11=0;
12534 new_r01=0;
12535 new_r22=0;
12536 new_r20=0;
12537 IkReal gconst9=((3.14159265358979)+(((-1.0)*x974)));
12538 IkReal gconst10=((1.0)*new_r10);
12539 IkReal gconst11=((1.0)*new_r00);
12540 j3eval[0]=-1.0;
12541 j3eval[1]=-1.0;
12542 j3eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10))));
12543 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
12544 {
12545 {
12546 IkReal j3eval[3];
12547 CheckValue<IkReal> x977 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12548 if(!x977.valid){
12549 continue;
12550 }
12551 IkReal x976=((1.0)*(x977.value));
12552 sj4=0;
12553 cj4=-1.0;
12554 j4=3.14159265358979;
12555 sj5=gconst10;
12556 cj5=gconst11;
12557 j5=((3.14159265)+(((-1.0)*x976)));
12558 new_r11=0;
12559 new_r01=0;
12560 new_r22=0;
12561 new_r20=0;
12562 IkReal gconst9=((3.14159265358979)+(((-1.0)*x976)));
12563 IkReal gconst10=((1.0)*new_r10);
12564 IkReal gconst11=((1.0)*new_r00);
12565 j3eval[0]=-1.0;
12566 j3eval[1]=-1.0;
12567 j3eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10))));
12568 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
12569 {
12570 {
12571 IkReal j3eval[3];
12572 CheckValue<IkReal> x979 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12573 if(!x979.valid){
12574 continue;
12575 }
12576 IkReal x978=((1.0)*(x979.value));
12577 sj4=0;
12578 cj4=-1.0;
12579 j4=3.14159265358979;
12580 sj5=gconst10;
12581 cj5=gconst11;
12582 j5=((3.14159265)+(((-1.0)*x978)));
12583 new_r11=0;
12584 new_r01=0;
12585 new_r22=0;
12586 new_r20=0;
12587 IkReal gconst9=((3.14159265358979)+(((-1.0)*x978)));
12588 IkReal gconst10=((1.0)*new_r10);
12589 IkReal gconst11=((1.0)*new_r00);
12590 j3eval[0]=-1.0;
12591 j3eval[1]=-1.0;
12592 j3eval[2]=((IKabs(((1.0)+(((-2.0)*(new_r10*new_r10))))))+(IKabs(((2.0)*new_r00*new_r10))));
12593 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
12594 {
12595 continue; // 3 cases reached
12596 
12597 } else
12598 {
12599 {
12600 IkReal j3array[1], cj3array[1], sj3array[1];
12601 bool j3valid[1]={false};
12602 _nj3 = 1;
12603 CheckValue<IkReal> x980 = IKatan2WithCheck(IkReal((((gconst10*gconst11))+((new_r00*new_r10)))),IkReal(((((-1.0)*(new_r10*new_r10)))+(gconst11*gconst11))),IKFAST_ATAN2_MAGTHRESH);
12604 if(!x980.valid){
12605 continue;
12606 }
12607 CheckValue<IkReal> x981=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst10*new_r10))+(((-1.0)*gconst11*new_r00)))),-1);
12608 if(!x981.valid){
12609 continue;
12610 }
12611 j3array[0]=((-1.5707963267949)+(x980.value)+(((1.5707963267949)*(x981.value))));
12612 sj3array[0]=IKsin(j3array[0]);
12613 cj3array[0]=IKcos(j3array[0]);
12614 if( j3array[0] > IKPI )
12615 {
12616  j3array[0]-=IK2PI;
12617 }
12618 else if( j3array[0] < -IKPI )
12619 { j3array[0]+=IK2PI;
12620 }
12621 j3valid[0] = true;
12622 for(int ij3 = 0; ij3 < 1; ++ij3)
12623 {
12624 if( !j3valid[ij3] )
12625 {
12626  continue;
12627 }
12628 _ij3[0] = ij3; _ij3[1] = -1;
12629 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12630 {
12631 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12632 {
12633  j3valid[iij3]=false; _ij3[1] = iij3; break;
12634 }
12635 }
12636 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12637 {
12638 IkReal evalcond[6];
12639 IkReal x982=IKsin(j3);
12640 IkReal x983=IKcos(j3);
12641 IkReal x984=(gconst11*x982);
12642 IkReal x985=(gconst10*x982);
12643 IkReal x986=(gconst11*x983);
12644 IkReal x987=((1.0)*x983);
12645 IkReal x988=(gconst10*x987);
12646 evalcond[0]=((((-1.0)*x988))+x984);
12647 evalcond[1]=(((new_r00*x983))+gconst11+((new_r10*x982)));
12648 evalcond[2]=(new_r00+x985+x986);
12649 evalcond[3]=(((new_r00*x982))+gconst10+(((-1.0)*new_r10*x987)));
12650 evalcond[4]=((((-1.0)*x985))+(((-1.0)*x986)));
12651 evalcond[5]=((((-1.0)*x988))+new_r10+x984);
12652 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
12653 {
12654 continue;
12655 }
12656 }
12657 
12658 {
12659 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12660 vinfos[0].jointtype = 1;
12661 vinfos[0].foffset = j0;
12662 vinfos[0].indices[0] = _ij0[0];
12663 vinfos[0].indices[1] = _ij0[1];
12664 vinfos[0].maxsolutions = _nj0;
12665 vinfos[1].jointtype = 1;
12666 vinfos[1].foffset = j1;
12667 vinfos[1].indices[0] = _ij1[0];
12668 vinfos[1].indices[1] = _ij1[1];
12669 vinfos[1].maxsolutions = _nj1;
12670 vinfos[2].jointtype = 1;
12671 vinfos[2].foffset = j2;
12672 vinfos[2].indices[0] = _ij2[0];
12673 vinfos[2].indices[1] = _ij2[1];
12674 vinfos[2].maxsolutions = _nj2;
12675 vinfos[3].jointtype = 1;
12676 vinfos[3].foffset = j3;
12677 vinfos[3].indices[0] = _ij3[0];
12678 vinfos[3].indices[1] = _ij3[1];
12679 vinfos[3].maxsolutions = _nj3;
12680 vinfos[4].jointtype = 1;
12681 vinfos[4].foffset = j4;
12682 vinfos[4].indices[0] = _ij4[0];
12683 vinfos[4].indices[1] = _ij4[1];
12684 vinfos[4].maxsolutions = _nj4;
12685 vinfos[5].jointtype = 1;
12686 vinfos[5].foffset = j5;
12687 vinfos[5].indices[0] = _ij5[0];
12688 vinfos[5].indices[1] = _ij5[1];
12689 vinfos[5].maxsolutions = _nj5;
12690 std::vector<int> vfree(0);
12691 solutions.AddSolution(vinfos,vfree);
12692 }
12693 }
12694 }
12695 
12696 }
12697 
12698 }
12699 
12700 } else
12701 {
12702 {
12703 IkReal j3array[1], cj3array[1], sj3array[1];
12704 bool j3valid[1]={false};
12705 _nj3 = 1;
12706 CheckValue<IkReal> x989=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst11*gconst11)))+(((-1.0)*(gconst10*gconst10))))),-1);
12707 if(!x989.valid){
12708 continue;
12709 }
12710 CheckValue<IkReal> x990 = IKatan2WithCheck(IkReal((gconst10*new_r00)),IkReal((gconst11*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12711 if(!x990.valid){
12712 continue;
12713 }
12714 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x989.value)))+(x990.value));
12715 sj3array[0]=IKsin(j3array[0]);
12716 cj3array[0]=IKcos(j3array[0]);
12717 if( j3array[0] > IKPI )
12718 {
12719  j3array[0]-=IK2PI;
12720 }
12721 else if( j3array[0] < -IKPI )
12722 { j3array[0]+=IK2PI;
12723 }
12724 j3valid[0] = true;
12725 for(int ij3 = 0; ij3 < 1; ++ij3)
12726 {
12727 if( !j3valid[ij3] )
12728 {
12729  continue;
12730 }
12731 _ij3[0] = ij3; _ij3[1] = -1;
12732 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12733 {
12734 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12735 {
12736  j3valid[iij3]=false; _ij3[1] = iij3; break;
12737 }
12738 }
12739 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12740 {
12741 IkReal evalcond[6];
12742 IkReal x991=IKsin(j3);
12743 IkReal x992=IKcos(j3);
12744 IkReal x993=(gconst11*x991);
12745 IkReal x994=(gconst10*x991);
12746 IkReal x995=(gconst11*x992);
12747 IkReal x996=((1.0)*x992);
12748 IkReal x997=(gconst10*x996);
12749 evalcond[0]=((((-1.0)*x997))+x993);
12750 evalcond[1]=(((new_r10*x991))+gconst11+((new_r00*x992)));
12751 evalcond[2]=(new_r00+x995+x994);
12752 evalcond[3]=((((-1.0)*new_r10*x996))+gconst10+((new_r00*x991)));
12753 evalcond[4]=((((-1.0)*x994))+(((-1.0)*x995)));
12754 evalcond[5]=((((-1.0)*x997))+new_r10+x993);
12755 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
12756 {
12757 continue;
12758 }
12759 }
12760 
12761 {
12762 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12763 vinfos[0].jointtype = 1;
12764 vinfos[0].foffset = j0;
12765 vinfos[0].indices[0] = _ij0[0];
12766 vinfos[0].indices[1] = _ij0[1];
12767 vinfos[0].maxsolutions = _nj0;
12768 vinfos[1].jointtype = 1;
12769 vinfos[1].foffset = j1;
12770 vinfos[1].indices[0] = _ij1[0];
12771 vinfos[1].indices[1] = _ij1[1];
12772 vinfos[1].maxsolutions = _nj1;
12773 vinfos[2].jointtype = 1;
12774 vinfos[2].foffset = j2;
12775 vinfos[2].indices[0] = _ij2[0];
12776 vinfos[2].indices[1] = _ij2[1];
12777 vinfos[2].maxsolutions = _nj2;
12778 vinfos[3].jointtype = 1;
12779 vinfos[3].foffset = j3;
12780 vinfos[3].indices[0] = _ij3[0];
12781 vinfos[3].indices[1] = _ij3[1];
12782 vinfos[3].maxsolutions = _nj3;
12783 vinfos[4].jointtype = 1;
12784 vinfos[4].foffset = j4;
12785 vinfos[4].indices[0] = _ij4[0];
12786 vinfos[4].indices[1] = _ij4[1];
12787 vinfos[4].maxsolutions = _nj4;
12788 vinfos[5].jointtype = 1;
12789 vinfos[5].foffset = j5;
12790 vinfos[5].indices[0] = _ij5[0];
12791 vinfos[5].indices[1] = _ij5[1];
12792 vinfos[5].maxsolutions = _nj5;
12793 std::vector<int> vfree(0);
12794 solutions.AddSolution(vinfos,vfree);
12795 }
12796 }
12797 }
12798 
12799 }
12800 
12801 }
12802 
12803 } else
12804 {
12805 {
12806 IkReal j3array[1], cj3array[1], sj3array[1];
12807 bool j3valid[1]={false};
12808 _nj3 = 1;
12809 CheckValue<IkReal> x998 = IKatan2WithCheck(IkReal((gconst10*gconst11)),IkReal(gconst11*gconst11),IKFAST_ATAN2_MAGTHRESH);
12810 if(!x998.valid){
12811 continue;
12812 }
12813 CheckValue<IkReal> x999=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst10*new_r10))+(((-1.0)*gconst11*new_r00)))),-1);
12814 if(!x999.valid){
12815 continue;
12816 }
12817 j3array[0]=((-1.5707963267949)+(x998.value)+(((1.5707963267949)*(x999.value))));
12818 sj3array[0]=IKsin(j3array[0]);
12819 cj3array[0]=IKcos(j3array[0]);
12820 if( j3array[0] > IKPI )
12821 {
12822  j3array[0]-=IK2PI;
12823 }
12824 else if( j3array[0] < -IKPI )
12825 { j3array[0]+=IK2PI;
12826 }
12827 j3valid[0] = true;
12828 for(int ij3 = 0; ij3 < 1; ++ij3)
12829 {
12830 if( !j3valid[ij3] )
12831 {
12832  continue;
12833 }
12834 _ij3[0] = ij3; _ij3[1] = -1;
12835 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12836 {
12837 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12838 {
12839  j3valid[iij3]=false; _ij3[1] = iij3; break;
12840 }
12841 }
12842 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12843 {
12844 IkReal evalcond[6];
12845 IkReal x1000=IKsin(j3);
12846 IkReal x1001=IKcos(j3);
12847 IkReal x1002=(gconst11*x1000);
12848 IkReal x1003=(gconst10*x1000);
12849 IkReal x1004=(gconst11*x1001);
12850 IkReal x1005=((1.0)*x1001);
12851 IkReal x1006=(gconst10*x1005);
12852 evalcond[0]=(x1002+(((-1.0)*x1006)));
12853 evalcond[1]=(gconst11+((new_r10*x1000))+((new_r00*x1001)));
12854 evalcond[2]=(x1004+x1003+new_r00);
12855 evalcond[3]=(gconst10+(((-1.0)*new_r10*x1005))+((new_r00*x1000)));
12856 evalcond[4]=((((-1.0)*x1003))+(((-1.0)*x1004)));
12857 evalcond[5]=(x1002+(((-1.0)*x1006))+new_r10);
12858 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
12859 {
12860 continue;
12861 }
12862 }
12863 
12864 {
12865 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12866 vinfos[0].jointtype = 1;
12867 vinfos[0].foffset = j0;
12868 vinfos[0].indices[0] = _ij0[0];
12869 vinfos[0].indices[1] = _ij0[1];
12870 vinfos[0].maxsolutions = _nj0;
12871 vinfos[1].jointtype = 1;
12872 vinfos[1].foffset = j1;
12873 vinfos[1].indices[0] = _ij1[0];
12874 vinfos[1].indices[1] = _ij1[1];
12875 vinfos[1].maxsolutions = _nj1;
12876 vinfos[2].jointtype = 1;
12877 vinfos[2].foffset = j2;
12878 vinfos[2].indices[0] = _ij2[0];
12879 vinfos[2].indices[1] = _ij2[1];
12880 vinfos[2].maxsolutions = _nj2;
12881 vinfos[3].jointtype = 1;
12882 vinfos[3].foffset = j3;
12883 vinfos[3].indices[0] = _ij3[0];
12884 vinfos[3].indices[1] = _ij3[1];
12885 vinfos[3].maxsolutions = _nj3;
12886 vinfos[4].jointtype = 1;
12887 vinfos[4].foffset = j4;
12888 vinfos[4].indices[0] = _ij4[0];
12889 vinfos[4].indices[1] = _ij4[1];
12890 vinfos[4].maxsolutions = _nj4;
12891 vinfos[5].jointtype = 1;
12892 vinfos[5].foffset = j5;
12893 vinfos[5].indices[0] = _ij5[0];
12894 vinfos[5].indices[1] = _ij5[1];
12895 vinfos[5].maxsolutions = _nj5;
12896 std::vector<int> vfree(0);
12897 solutions.AddSolution(vinfos,vfree);
12898 }
12899 }
12900 }
12901 
12902 }
12903 
12904 }
12905 
12906 }
12907 } while(0);
12908 if( bgotonextstatement )
12909 {
12910 bool bgotonextstatement = true;
12911 do
12912 {
12913 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
12914 if( IKabs(evalcond[0]) < 0.0000050000000000 )
12915 {
12916 bgotonextstatement=false;
12917 {
12918 IkReal j3eval[1];
12919 CheckValue<IkReal> x1008 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
12920 if(!x1008.valid){
12921 continue;
12922 }
12923 IkReal x1007=((1.0)*(x1008.value));
12924 sj4=0;
12925 cj4=-1.0;
12926 j4=3.14159265358979;
12927 sj5=gconst10;
12928 cj5=gconst11;
12929 j5=((3.14159265)+(((-1.0)*x1007)));
12930 new_r01=0;
12931 new_r10=0;
12932 IkReal gconst9=((3.14159265358979)+(((-1.0)*x1007)));
12933 IkReal gconst10=0;
12934 IkReal x1009 = new_r00*new_r00;
12935 if(IKabs(x1009)==0){
12936 continue;
12937 }
12938 IkReal gconst11=((1.0)*new_r00*(pow(x1009,-0.5)));
12939 j3eval[0]=new_r11;
12940 if( IKabs(j3eval[0]) < 0.0000010000000000 )
12941 {
12942 {
12943 IkReal j3array[2], cj3array[2], sj3array[2];
12944 bool j3valid[2]={false};
12945 _nj3 = 2;
12946 CheckValue<IkReal> x1010=IKPowWithIntegerCheck(gconst11,-1);
12947 if(!x1010.valid){
12948 continue;
12949 }
12950 cj3array[0]=(new_r11*(x1010.value));
12951 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
12952 {
12953  j3valid[0] = j3valid[1] = true;
12954  j3array[0] = IKacos(cj3array[0]);
12955  sj3array[0] = IKsin(j3array[0]);
12956  cj3array[1] = cj3array[0];
12957  j3array[1] = -j3array[0];
12958  sj3array[1] = -sj3array[0];
12959 }
12960 else if( isnan(cj3array[0]) )
12961 {
12962  // probably any value will work
12963  j3valid[0] = true;
12964  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
12965 }
12966 for(int ij3 = 0; ij3 < 2; ++ij3)
12967 {
12968 if( !j3valid[ij3] )
12969 {
12970  continue;
12971 }
12972 _ij3[0] = ij3; _ij3[1] = -1;
12973 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
12974 {
12975 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12976 {
12977  j3valid[iij3]=false; _ij3[1] = iij3; break;
12978 }
12979 }
12980 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12981 {
12982 IkReal evalcond[6];
12983 IkReal x1011=IKsin(j3);
12984 IkReal x1012=IKcos(j3);
12985 evalcond[0]=(new_r00*x1011);
12986 evalcond[1]=(new_r11*x1011);
12987 evalcond[2]=(gconst11*x1011);
12988 evalcond[3]=(gconst11+((new_r00*x1012)));
12989 evalcond[4]=(((gconst11*x1012))+new_r00);
12990 evalcond[5]=((((-1.0)*new_r11*x1012))+gconst11);
12991 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
12992 {
12993 continue;
12994 }
12995 }
12996 
12997 {
12998 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12999 vinfos[0].jointtype = 1;
13000 vinfos[0].foffset = j0;
13001 vinfos[0].indices[0] = _ij0[0];
13002 vinfos[0].indices[1] = _ij0[1];
13003 vinfos[0].maxsolutions = _nj0;
13004 vinfos[1].jointtype = 1;
13005 vinfos[1].foffset = j1;
13006 vinfos[1].indices[0] = _ij1[0];
13007 vinfos[1].indices[1] = _ij1[1];
13008 vinfos[1].maxsolutions = _nj1;
13009 vinfos[2].jointtype = 1;
13010 vinfos[2].foffset = j2;
13011 vinfos[2].indices[0] = _ij2[0];
13012 vinfos[2].indices[1] = _ij2[1];
13013 vinfos[2].maxsolutions = _nj2;
13014 vinfos[3].jointtype = 1;
13015 vinfos[3].foffset = j3;
13016 vinfos[3].indices[0] = _ij3[0];
13017 vinfos[3].indices[1] = _ij3[1];
13018 vinfos[3].maxsolutions = _nj3;
13019 vinfos[4].jointtype = 1;
13020 vinfos[4].foffset = j4;
13021 vinfos[4].indices[0] = _ij4[0];
13022 vinfos[4].indices[1] = _ij4[1];
13023 vinfos[4].maxsolutions = _nj4;
13024 vinfos[5].jointtype = 1;
13025 vinfos[5].foffset = j5;
13026 vinfos[5].indices[0] = _ij5[0];
13027 vinfos[5].indices[1] = _ij5[1];
13028 vinfos[5].maxsolutions = _nj5;
13029 std::vector<int> vfree(0);
13030 solutions.AddSolution(vinfos,vfree);
13031 }
13032 }
13033 }
13034 
13035 } else
13036 {
13037 {
13038 IkReal j3array[2], cj3array[2], sj3array[2];
13039 bool j3valid[2]={false};
13040 _nj3 = 2;
13041 CheckValue<IkReal> x1013=IKPowWithIntegerCheck(new_r11,-1);
13042 if(!x1013.valid){
13043 continue;
13044 }
13045 cj3array[0]=(gconst11*(x1013.value));
13046 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
13047 {
13048  j3valid[0] = j3valid[1] = true;
13049  j3array[0] = IKacos(cj3array[0]);
13050  sj3array[0] = IKsin(j3array[0]);
13051  cj3array[1] = cj3array[0];
13052  j3array[1] = -j3array[0];
13053  sj3array[1] = -sj3array[0];
13054 }
13055 else if( isnan(cj3array[0]) )
13056 {
13057  // probably any value will work
13058  j3valid[0] = true;
13059  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
13060 }
13061 for(int ij3 = 0; ij3 < 2; ++ij3)
13062 {
13063 if( !j3valid[ij3] )
13064 {
13065  continue;
13066 }
13067 _ij3[0] = ij3; _ij3[1] = -1;
13068 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
13069 {
13070 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13071 {
13072  j3valid[iij3]=false; _ij3[1] = iij3; break;
13073 }
13074 }
13075 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13076 {
13077 IkReal evalcond[6];
13078 IkReal x1014=IKsin(j3);
13079 IkReal x1015=IKcos(j3);
13080 IkReal x1016=(gconst11*x1015);
13081 evalcond[0]=(new_r00*x1014);
13082 evalcond[1]=(new_r11*x1014);
13083 evalcond[2]=(gconst11*x1014);
13084 evalcond[3]=(gconst11+((new_r00*x1015)));
13085 evalcond[4]=(x1016+new_r00);
13086 evalcond[5]=(new_r11+(((-1.0)*x1016)));
13087 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
13088 {
13089 continue;
13090 }
13091 }
13092 
13093 {
13094 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13095 vinfos[0].jointtype = 1;
13096 vinfos[0].foffset = j0;
13097 vinfos[0].indices[0] = _ij0[0];
13098 vinfos[0].indices[1] = _ij0[1];
13099 vinfos[0].maxsolutions = _nj0;
13100 vinfos[1].jointtype = 1;
13101 vinfos[1].foffset = j1;
13102 vinfos[1].indices[0] = _ij1[0];
13103 vinfos[1].indices[1] = _ij1[1];
13104 vinfos[1].maxsolutions = _nj1;
13105 vinfos[2].jointtype = 1;
13106 vinfos[2].foffset = j2;
13107 vinfos[2].indices[0] = _ij2[0];
13108 vinfos[2].indices[1] = _ij2[1];
13109 vinfos[2].maxsolutions = _nj2;
13110 vinfos[3].jointtype = 1;
13111 vinfos[3].foffset = j3;
13112 vinfos[3].indices[0] = _ij3[0];
13113 vinfos[3].indices[1] = _ij3[1];
13114 vinfos[3].maxsolutions = _nj3;
13115 vinfos[4].jointtype = 1;
13116 vinfos[4].foffset = j4;
13117 vinfos[4].indices[0] = _ij4[0];
13118 vinfos[4].indices[1] = _ij4[1];
13119 vinfos[4].maxsolutions = _nj4;
13120 vinfos[5].jointtype = 1;
13121 vinfos[5].foffset = j5;
13122 vinfos[5].indices[0] = _ij5[0];
13123 vinfos[5].indices[1] = _ij5[1];
13124 vinfos[5].maxsolutions = _nj5;
13125 std::vector<int> vfree(0);
13126 solutions.AddSolution(vinfos,vfree);
13127 }
13128 }
13129 }
13130 
13131 }
13132 
13133 }
13134 
13135 }
13136 } while(0);
13137 if( bgotonextstatement )
13138 {
13139 bool bgotonextstatement = true;
13140 do
13141 {
13142 evalcond[0]=IKabs(new_r00);
13143 if( IKabs(evalcond[0]) < 0.0000050000000000 )
13144 {
13145 bgotonextstatement=false;
13146 {
13147 IkReal j3eval[1];
13148 CheckValue<IkReal> x1018 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
13149 if(!x1018.valid){
13150 continue;
13151 }
13152 IkReal x1017=((1.0)*(x1018.value));
13153 sj4=0;
13154 cj4=-1.0;
13155 j4=3.14159265358979;
13156 sj5=gconst10;
13157 cj5=gconst11;
13158 j5=((3.14159265)+(((-1.0)*x1017)));
13159 new_r00=0;
13160 IkReal gconst9=((3.14159265358979)+(((-1.0)*x1017)));
13161 IkReal x1019 = new_r10*new_r10;
13162 if(IKabs(x1019)==0){
13163 continue;
13164 }
13165 IkReal gconst10=((1.0)*new_r10*(pow(x1019,-0.5)));
13166 IkReal gconst11=0;
13167 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
13168 if( IKabs(j3eval[0]) < 0.0000010000000000 )
13169 {
13170 {
13171 IkReal j3eval[1];
13172 CheckValue<IkReal> x1021 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
13173 if(!x1021.valid){
13174 continue;
13175 }
13176 IkReal x1020=((1.0)*(x1021.value));
13177 sj4=0;
13178 cj4=-1.0;
13179 j4=3.14159265358979;
13180 sj5=gconst10;
13181 cj5=gconst11;
13182 j5=((3.14159265)+(((-1.0)*x1020)));
13183 new_r00=0;
13184 IkReal gconst9=((3.14159265358979)+(((-1.0)*x1020)));
13185 IkReal x1022 = new_r10*new_r10;
13186 if(IKabs(x1022)==0){
13187 continue;
13188 }
13189 IkReal gconst10=((1.0)*new_r10*(pow(x1022,-0.5)));
13190 IkReal gconst11=0;
13191 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
13192 if( IKabs(j3eval[0]) < 0.0000010000000000 )
13193 {
13194 {
13195 IkReal j3eval[1];
13196 CheckValue<IkReal> x1024 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
13197 if(!x1024.valid){
13198 continue;
13199 }
13200 IkReal x1023=((1.0)*(x1024.value));
13201 sj4=0;
13202 cj4=-1.0;
13203 j4=3.14159265358979;
13204 sj5=gconst10;
13205 cj5=gconst11;
13206 j5=((3.14159265)+(((-1.0)*x1023)));
13207 new_r00=0;
13208 IkReal gconst9=((3.14159265358979)+(((-1.0)*x1023)));
13209 IkReal x1025 = new_r10*new_r10;
13210 if(IKabs(x1025)==0){
13211 continue;
13212 }
13213 IkReal gconst10=((1.0)*new_r10*(pow(x1025,-0.5)));
13214 IkReal gconst11=0;
13215 j3eval[0]=new_r10;
13216 if( IKabs(j3eval[0]) < 0.0000010000000000 )
13217 {
13218 continue; // 3 cases reached
13219 
13220 } else
13221 {
13222 {
13223 IkReal j3array[1], cj3array[1], sj3array[1];
13224 bool j3valid[1]={false};
13225 _nj3 = 1;
13226 CheckValue<IkReal> x1026=IKPowWithIntegerCheck(gconst10,-1);
13227 if(!x1026.valid){
13228 continue;
13229 }
13230 CheckValue<IkReal> x1027=IKPowWithIntegerCheck(new_r10,-1);
13231 if(!x1027.valid){
13232 continue;
13233 }
13234 if( IKabs((new_r11*(x1026.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst10*(x1027.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r11*(x1026.value)))+IKsqr((gconst10*(x1027.value)))-1) <= IKFAST_SINCOS_THRESH )
13235  continue;
13236 j3array[0]=IKatan2((new_r11*(x1026.value)), (gconst10*(x1027.value)));
13237 sj3array[0]=IKsin(j3array[0]);
13238 cj3array[0]=IKcos(j3array[0]);
13239 if( j3array[0] > IKPI )
13240 {
13241  j3array[0]-=IK2PI;
13242 }
13243 else if( j3array[0] < -IKPI )
13244 { j3array[0]+=IK2PI;
13245 }
13246 j3valid[0] = true;
13247 for(int ij3 = 0; ij3 < 1; ++ij3)
13248 {
13249 if( !j3valid[ij3] )
13250 {
13251  continue;
13252 }
13253 _ij3[0] = ij3; _ij3[1] = -1;
13254 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13255 {
13256 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13257 {
13258  j3valid[iij3]=false; _ij3[1] = iij3; break;
13259 }
13260 }
13261 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13262 {
13263 IkReal evalcond[8];
13264 IkReal x1028=IKsin(j3);
13265 IkReal x1029=IKcos(j3);
13266 IkReal x1030=(gconst10*x1028);
13267 IkReal x1031=((1.0)*x1029);
13268 IkReal x1032=(gconst10*x1031);
13269 evalcond[0]=(new_r10*x1028);
13270 evalcond[1]=x1030;
13271 evalcond[2]=(gconst10+(((-1.0)*new_r10*x1031)));
13272 evalcond[3]=((((-1.0)*x1032))+new_r01);
13273 evalcond[4]=((((-1.0)*x1030))+new_r11);
13274 evalcond[5]=((((-1.0)*x1032))+new_r10);
13275 evalcond[6]=((((-1.0)*new_r11*x1031))+((new_r01*x1028)));
13276 evalcond[7]=(((new_r11*x1028))+(((-1.0)*gconst10))+((new_r01*x1029)));
13277 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
13278 {
13279 continue;
13280 }
13281 }
13282 
13283 {
13284 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13285 vinfos[0].jointtype = 1;
13286 vinfos[0].foffset = j0;
13287 vinfos[0].indices[0] = _ij0[0];
13288 vinfos[0].indices[1] = _ij0[1];
13289 vinfos[0].maxsolutions = _nj0;
13290 vinfos[1].jointtype = 1;
13291 vinfos[1].foffset = j1;
13292 vinfos[1].indices[0] = _ij1[0];
13293 vinfos[1].indices[1] = _ij1[1];
13294 vinfos[1].maxsolutions = _nj1;
13295 vinfos[2].jointtype = 1;
13296 vinfos[2].foffset = j2;
13297 vinfos[2].indices[0] = _ij2[0];
13298 vinfos[2].indices[1] = _ij2[1];
13299 vinfos[2].maxsolutions = _nj2;
13300 vinfos[3].jointtype = 1;
13301 vinfos[3].foffset = j3;
13302 vinfos[3].indices[0] = _ij3[0];
13303 vinfos[3].indices[1] = _ij3[1];
13304 vinfos[3].maxsolutions = _nj3;
13305 vinfos[4].jointtype = 1;
13306 vinfos[4].foffset = j4;
13307 vinfos[4].indices[0] = _ij4[0];
13308 vinfos[4].indices[1] = _ij4[1];
13309 vinfos[4].maxsolutions = _nj4;
13310 vinfos[5].jointtype = 1;
13311 vinfos[5].foffset = j5;
13312 vinfos[5].indices[0] = _ij5[0];
13313 vinfos[5].indices[1] = _ij5[1];
13314 vinfos[5].maxsolutions = _nj5;
13315 std::vector<int> vfree(0);
13316 solutions.AddSolution(vinfos,vfree);
13317 }
13318 }
13319 }
13320 
13321 }
13322 
13323 }
13324 
13325 } else
13326 {
13327 {
13328 IkReal j3array[1], cj3array[1], sj3array[1];
13329 bool j3valid[1]={false};
13330 _nj3 = 1;
13331 CheckValue<IkReal> x1033=IKPowWithIntegerCheck(IKsign(gconst10),-1);
13332 if(!x1033.valid){
13333 continue;
13334 }
13335 CheckValue<IkReal> x1034 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
13336 if(!x1034.valid){
13337 continue;
13338 }
13339 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1033.value)))+(x1034.value));
13340 sj3array[0]=IKsin(j3array[0]);
13341 cj3array[0]=IKcos(j3array[0]);
13342 if( j3array[0] > IKPI )
13343 {
13344  j3array[0]-=IK2PI;
13345 }
13346 else if( j3array[0] < -IKPI )
13347 { j3array[0]+=IK2PI;
13348 }
13349 j3valid[0] = true;
13350 for(int ij3 = 0; ij3 < 1; ++ij3)
13351 {
13352 if( !j3valid[ij3] )
13353 {
13354  continue;
13355 }
13356 _ij3[0] = ij3; _ij3[1] = -1;
13357 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13358 {
13359 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13360 {
13361  j3valid[iij3]=false; _ij3[1] = iij3; break;
13362 }
13363 }
13364 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13365 {
13366 IkReal evalcond[8];
13367 IkReal x1035=IKsin(j3);
13368 IkReal x1036=IKcos(j3);
13369 IkReal x1037=(gconst10*x1035);
13370 IkReal x1038=((1.0)*x1036);
13371 IkReal x1039=(gconst10*x1038);
13372 evalcond[0]=(new_r10*x1035);
13373 evalcond[1]=x1037;
13374 evalcond[2]=(gconst10+(((-1.0)*new_r10*x1038)));
13375 evalcond[3]=((((-1.0)*x1039))+new_r01);
13376 evalcond[4]=((((-1.0)*x1037))+new_r11);
13377 evalcond[5]=((((-1.0)*x1039))+new_r10);
13378 evalcond[6]=((((-1.0)*new_r11*x1038))+((new_r01*x1035)));
13379 evalcond[7]=(((new_r11*x1035))+(((-1.0)*gconst10))+((new_r01*x1036)));
13380 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
13381 {
13382 continue;
13383 }
13384 }
13385 
13386 {
13387 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13388 vinfos[0].jointtype = 1;
13389 vinfos[0].foffset = j0;
13390 vinfos[0].indices[0] = _ij0[0];
13391 vinfos[0].indices[1] = _ij0[1];
13392 vinfos[0].maxsolutions = _nj0;
13393 vinfos[1].jointtype = 1;
13394 vinfos[1].foffset = j1;
13395 vinfos[1].indices[0] = _ij1[0];
13396 vinfos[1].indices[1] = _ij1[1];
13397 vinfos[1].maxsolutions = _nj1;
13398 vinfos[2].jointtype = 1;
13399 vinfos[2].foffset = j2;
13400 vinfos[2].indices[0] = _ij2[0];
13401 vinfos[2].indices[1] = _ij2[1];
13402 vinfos[2].maxsolutions = _nj2;
13403 vinfos[3].jointtype = 1;
13404 vinfos[3].foffset = j3;
13405 vinfos[3].indices[0] = _ij3[0];
13406 vinfos[3].indices[1] = _ij3[1];
13407 vinfos[3].maxsolutions = _nj3;
13408 vinfos[4].jointtype = 1;
13409 vinfos[4].foffset = j4;
13410 vinfos[4].indices[0] = _ij4[0];
13411 vinfos[4].indices[1] = _ij4[1];
13412 vinfos[4].maxsolutions = _nj4;
13413 vinfos[5].jointtype = 1;
13414 vinfos[5].foffset = j5;
13415 vinfos[5].indices[0] = _ij5[0];
13416 vinfos[5].indices[1] = _ij5[1];
13417 vinfos[5].maxsolutions = _nj5;
13418 std::vector<int> vfree(0);
13419 solutions.AddSolution(vinfos,vfree);
13420 }
13421 }
13422 }
13423 
13424 }
13425 
13426 }
13427 
13428 } else
13429 {
13430 {
13431 IkReal j3array[1], cj3array[1], sj3array[1];
13432 bool j3valid[1]={false};
13433 _nj3 = 1;
13434 CheckValue<IkReal> x1040=IKPowWithIntegerCheck(IKsign(gconst10),-1);
13435 if(!x1040.valid){
13436 continue;
13437 }
13438 CheckValue<IkReal> x1041 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
13439 if(!x1041.valid){
13440 continue;
13441 }
13442 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1040.value)))+(x1041.value));
13443 sj3array[0]=IKsin(j3array[0]);
13444 cj3array[0]=IKcos(j3array[0]);
13445 if( j3array[0] > IKPI )
13446 {
13447  j3array[0]-=IK2PI;
13448 }
13449 else if( j3array[0] < -IKPI )
13450 { j3array[0]+=IK2PI;
13451 }
13452 j3valid[0] = true;
13453 for(int ij3 = 0; ij3 < 1; ++ij3)
13454 {
13455 if( !j3valid[ij3] )
13456 {
13457  continue;
13458 }
13459 _ij3[0] = ij3; _ij3[1] = -1;
13460 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13461 {
13462 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13463 {
13464  j3valid[iij3]=false; _ij3[1] = iij3; break;
13465 }
13466 }
13467 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13468 {
13469 IkReal evalcond[8];
13470 IkReal x1042=IKsin(j3);
13471 IkReal x1043=IKcos(j3);
13472 IkReal x1044=(gconst10*x1042);
13473 IkReal x1045=((1.0)*x1043);
13474 IkReal x1046=(gconst10*x1045);
13475 evalcond[0]=(new_r10*x1042);
13476 evalcond[1]=x1044;
13477 evalcond[2]=(gconst10+(((-1.0)*new_r10*x1045)));
13478 evalcond[3]=(new_r01+(((-1.0)*x1046)));
13479 evalcond[4]=((((-1.0)*x1044))+new_r11);
13480 evalcond[5]=(new_r10+(((-1.0)*x1046)));
13481 evalcond[6]=(((new_r01*x1042))+(((-1.0)*new_r11*x1045)));
13482 evalcond[7]=(((new_r11*x1042))+((new_r01*x1043))+(((-1.0)*gconst10)));
13483 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
13484 {
13485 continue;
13486 }
13487 }
13488 
13489 {
13490 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13491 vinfos[0].jointtype = 1;
13492 vinfos[0].foffset = j0;
13493 vinfos[0].indices[0] = _ij0[0];
13494 vinfos[0].indices[1] = _ij0[1];
13495 vinfos[0].maxsolutions = _nj0;
13496 vinfos[1].jointtype = 1;
13497 vinfos[1].foffset = j1;
13498 vinfos[1].indices[0] = _ij1[0];
13499 vinfos[1].indices[1] = _ij1[1];
13500 vinfos[1].maxsolutions = _nj1;
13501 vinfos[2].jointtype = 1;
13502 vinfos[2].foffset = j2;
13503 vinfos[2].indices[0] = _ij2[0];
13504 vinfos[2].indices[1] = _ij2[1];
13505 vinfos[2].maxsolutions = _nj2;
13506 vinfos[3].jointtype = 1;
13507 vinfos[3].foffset = j3;
13508 vinfos[3].indices[0] = _ij3[0];
13509 vinfos[3].indices[1] = _ij3[1];
13510 vinfos[3].maxsolutions = _nj3;
13511 vinfos[4].jointtype = 1;
13512 vinfos[4].foffset = j4;
13513 vinfos[4].indices[0] = _ij4[0];
13514 vinfos[4].indices[1] = _ij4[1];
13515 vinfos[4].maxsolutions = _nj4;
13516 vinfos[5].jointtype = 1;
13517 vinfos[5].foffset = j5;
13518 vinfos[5].indices[0] = _ij5[0];
13519 vinfos[5].indices[1] = _ij5[1];
13520 vinfos[5].maxsolutions = _nj5;
13521 std::vector<int> vfree(0);
13522 solutions.AddSolution(vinfos,vfree);
13523 }
13524 }
13525 }
13526 
13527 }
13528 
13529 }
13530 
13531 }
13532 } while(0);
13533 if( bgotonextstatement )
13534 {
13535 bool bgotonextstatement = true;
13536 do
13537 {
13538 if( 1 )
13539 {
13540 bgotonextstatement=false;
13541 continue; // branch miss [j3]
13542 
13543 }
13544 } while(0);
13545 if( bgotonextstatement )
13546 {
13547 }
13548 }
13549 }
13550 }
13551 }
13552 }
13553 
13554 } else
13555 {
13556 {
13557 IkReal j3array[1], cj3array[1], sj3array[1];
13558 bool j3valid[1]={false};
13559 _nj3 = 1;
13560 CheckValue<IkReal> x1047 = IKatan2WithCheck(IkReal((((gconst10*gconst11))+((new_r00*new_r10)))),IkReal(((((-1.0)*(new_r10*new_r10)))+(gconst11*gconst11))),IKFAST_ATAN2_MAGTHRESH);
13561 if(!x1047.valid){
13562 continue;
13563 }
13564 CheckValue<IkReal> x1048=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst10*new_r10))+(((-1.0)*gconst11*new_r00)))),-1);
13565 if(!x1048.valid){
13566 continue;
13567 }
13568 j3array[0]=((-1.5707963267949)+(x1047.value)+(((1.5707963267949)*(x1048.value))));
13569 sj3array[0]=IKsin(j3array[0]);
13570 cj3array[0]=IKcos(j3array[0]);
13571 if( j3array[0] > IKPI )
13572 {
13573  j3array[0]-=IK2PI;
13574 }
13575 else if( j3array[0] < -IKPI )
13576 { j3array[0]+=IK2PI;
13577 }
13578 j3valid[0] = true;
13579 for(int ij3 = 0; ij3 < 1; ++ij3)
13580 {
13581 if( !j3valid[ij3] )
13582 {
13583  continue;
13584 }
13585 _ij3[0] = ij3; _ij3[1] = -1;
13586 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13587 {
13588 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13589 {
13590  j3valid[iij3]=false; _ij3[1] = iij3; break;
13591 }
13592 }
13593 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13594 {
13595 IkReal evalcond[8];
13596 IkReal x1049=IKcos(j3);
13597 IkReal x1050=IKsin(j3);
13598 IkReal x1051=((1.0)*gconst10);
13599 IkReal x1052=(gconst11*x1050);
13600 IkReal x1053=(gconst10*x1050);
13601 IkReal x1054=(gconst11*x1049);
13602 IkReal x1055=((1.0)*x1049);
13603 IkReal x1056=(x1049*x1051);
13604 evalcond[0]=(gconst11+((new_r00*x1049))+((new_r10*x1050)));
13605 evalcond[1]=(x1053+x1054+new_r00);
13606 evalcond[2]=(gconst10+((new_r00*x1050))+(((-1.0)*new_r10*x1055)));
13607 evalcond[3]=(gconst11+((new_r01*x1050))+(((-1.0)*new_r11*x1055)));
13608 evalcond[4]=((((-1.0)*x1056))+x1052+new_r01);
13609 evalcond[5]=((((-1.0)*x1056))+x1052+new_r10);
13610 evalcond[6]=((((-1.0)*x1051))+((new_r01*x1049))+((new_r11*x1050)));
13611 evalcond[7]=((((-1.0)*x1054))+new_r11+(((-1.0)*x1050*x1051)));
13612 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
13613 {
13614 continue;
13615 }
13616 }
13617 
13618 {
13619 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13620 vinfos[0].jointtype = 1;
13621 vinfos[0].foffset = j0;
13622 vinfos[0].indices[0] = _ij0[0];
13623 vinfos[0].indices[1] = _ij0[1];
13624 vinfos[0].maxsolutions = _nj0;
13625 vinfos[1].jointtype = 1;
13626 vinfos[1].foffset = j1;
13627 vinfos[1].indices[0] = _ij1[0];
13628 vinfos[1].indices[1] = _ij1[1];
13629 vinfos[1].maxsolutions = _nj1;
13630 vinfos[2].jointtype = 1;
13631 vinfos[2].foffset = j2;
13632 vinfos[2].indices[0] = _ij2[0];
13633 vinfos[2].indices[1] = _ij2[1];
13634 vinfos[2].maxsolutions = _nj2;
13635 vinfos[3].jointtype = 1;
13636 vinfos[3].foffset = j3;
13637 vinfos[3].indices[0] = _ij3[0];
13638 vinfos[3].indices[1] = _ij3[1];
13639 vinfos[3].maxsolutions = _nj3;
13640 vinfos[4].jointtype = 1;
13641 vinfos[4].foffset = j4;
13642 vinfos[4].indices[0] = _ij4[0];
13643 vinfos[4].indices[1] = _ij4[1];
13644 vinfos[4].maxsolutions = _nj4;
13645 vinfos[5].jointtype = 1;
13646 vinfos[5].foffset = j5;
13647 vinfos[5].indices[0] = _ij5[0];
13648 vinfos[5].indices[1] = _ij5[1];
13649 vinfos[5].maxsolutions = _nj5;
13650 std::vector<int> vfree(0);
13651 solutions.AddSolution(vinfos,vfree);
13652 }
13653 }
13654 }
13655 
13656 }
13657 
13658 }
13659 
13660 } else
13661 {
13662 {
13663 IkReal j3array[1], cj3array[1], sj3array[1];
13664 bool j3valid[1]={false};
13665 _nj3 = 1;
13666 IkReal x1057=((1.0)*new_r10);
13667 CheckValue<IkReal> x1058 = IKatan2WithCheck(IkReal((((gconst10*gconst11))+((new_r00*new_r01)))),IkReal(((((-1.0)*new_r01*x1057))+(gconst11*gconst11))),IKFAST_ATAN2_MAGTHRESH);
13668 if(!x1058.valid){
13669 continue;
13670 }
13671 CheckValue<IkReal> x1059=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst10*x1057))+(((-1.0)*gconst11*new_r00)))),-1);
13672 if(!x1059.valid){
13673 continue;
13674 }
13675 j3array[0]=((-1.5707963267949)+(x1058.value)+(((1.5707963267949)*(x1059.value))));
13676 sj3array[0]=IKsin(j3array[0]);
13677 cj3array[0]=IKcos(j3array[0]);
13678 if( j3array[0] > IKPI )
13679 {
13680  j3array[0]-=IK2PI;
13681 }
13682 else if( j3array[0] < -IKPI )
13683 { j3array[0]+=IK2PI;
13684 }
13685 j3valid[0] = true;
13686 for(int ij3 = 0; ij3 < 1; ++ij3)
13687 {
13688 if( !j3valid[ij3] )
13689 {
13690  continue;
13691 }
13692 _ij3[0] = ij3; _ij3[1] = -1;
13693 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13694 {
13695 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13696 {
13697  j3valid[iij3]=false; _ij3[1] = iij3; break;
13698 }
13699 }
13700 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13701 {
13702 IkReal evalcond[8];
13703 IkReal x1060=IKcos(j3);
13704 IkReal x1061=IKsin(j3);
13705 IkReal x1062=((1.0)*gconst10);
13706 IkReal x1063=(gconst11*x1061);
13707 IkReal x1064=(gconst10*x1061);
13708 IkReal x1065=(gconst11*x1060);
13709 IkReal x1066=((1.0)*x1060);
13710 IkReal x1067=(x1060*x1062);
13711 evalcond[0]=(gconst11+((new_r00*x1060))+((new_r10*x1061)));
13712 evalcond[1]=(x1065+x1064+new_r00);
13713 evalcond[2]=((((-1.0)*new_r10*x1066))+gconst10+((new_r00*x1061)));
13714 evalcond[3]=(gconst11+((new_r01*x1061))+(((-1.0)*new_r11*x1066)));
13715 evalcond[4]=(x1063+new_r01+(((-1.0)*x1067)));
13716 evalcond[5]=(x1063+new_r10+(((-1.0)*x1067)));
13717 evalcond[6]=(((new_r01*x1060))+((new_r11*x1061))+(((-1.0)*x1062)));
13718 evalcond[7]=((((-1.0)*x1061*x1062))+new_r11+(((-1.0)*x1065)));
13719 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
13720 {
13721 continue;
13722 }
13723 }
13724 
13725 {
13726 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13727 vinfos[0].jointtype = 1;
13728 vinfos[0].foffset = j0;
13729 vinfos[0].indices[0] = _ij0[0];
13730 vinfos[0].indices[1] = _ij0[1];
13731 vinfos[0].maxsolutions = _nj0;
13732 vinfos[1].jointtype = 1;
13733 vinfos[1].foffset = j1;
13734 vinfos[1].indices[0] = _ij1[0];
13735 vinfos[1].indices[1] = _ij1[1];
13736 vinfos[1].maxsolutions = _nj1;
13737 vinfos[2].jointtype = 1;
13738 vinfos[2].foffset = j2;
13739 vinfos[2].indices[0] = _ij2[0];
13740 vinfos[2].indices[1] = _ij2[1];
13741 vinfos[2].maxsolutions = _nj2;
13742 vinfos[3].jointtype = 1;
13743 vinfos[3].foffset = j3;
13744 vinfos[3].indices[0] = _ij3[0];
13745 vinfos[3].indices[1] = _ij3[1];
13746 vinfos[3].maxsolutions = _nj3;
13747 vinfos[4].jointtype = 1;
13748 vinfos[4].foffset = j4;
13749 vinfos[4].indices[0] = _ij4[0];
13750 vinfos[4].indices[1] = _ij4[1];
13751 vinfos[4].maxsolutions = _nj4;
13752 vinfos[5].jointtype = 1;
13753 vinfos[5].foffset = j5;
13754 vinfos[5].indices[0] = _ij5[0];
13755 vinfos[5].indices[1] = _ij5[1];
13756 vinfos[5].maxsolutions = _nj5;
13757 std::vector<int> vfree(0);
13758 solutions.AddSolution(vinfos,vfree);
13759 }
13760 }
13761 }
13762 
13763 }
13764 
13765 }
13766 
13767 } else
13768 {
13769 {
13770 IkReal j3array[1], cj3array[1], sj3array[1];
13771 bool j3valid[1]={false};
13772 _nj3 = 1;
13773 IkReal x1068=((1.0)*new_r10);
13774 CheckValue<IkReal> x1069=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*new_r01))+(((-1.0)*new_r11*x1068)))),-1);
13775 if(!x1069.valid){
13776 continue;
13777 }
13778 CheckValue<IkReal> x1070 = IKatan2WithCheck(IkReal((((gconst11*new_r00))+((gconst11*new_r11)))),IkReal((((gconst11*new_r01))+(((-1.0)*gconst11*x1068)))),IKFAST_ATAN2_MAGTHRESH);
13779 if(!x1070.valid){
13780 continue;
13781 }
13782 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1069.value)))+(x1070.value));
13783 sj3array[0]=IKsin(j3array[0]);
13784 cj3array[0]=IKcos(j3array[0]);
13785 if( j3array[0] > IKPI )
13786 {
13787  j3array[0]-=IK2PI;
13788 }
13789 else if( j3array[0] < -IKPI )
13790 { j3array[0]+=IK2PI;
13791 }
13792 j3valid[0] = true;
13793 for(int ij3 = 0; ij3 < 1; ++ij3)
13794 {
13795 if( !j3valid[ij3] )
13796 {
13797  continue;
13798 }
13799 _ij3[0] = ij3; _ij3[1] = -1;
13800 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13801 {
13802 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13803 {
13804  j3valid[iij3]=false; _ij3[1] = iij3; break;
13805 }
13806 }
13807 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13808 {
13809 IkReal evalcond[8];
13810 IkReal x1071=IKcos(j3);
13811 IkReal x1072=IKsin(j3);
13812 IkReal x1073=((1.0)*gconst10);
13813 IkReal x1074=(gconst11*x1072);
13814 IkReal x1075=(gconst10*x1072);
13815 IkReal x1076=(gconst11*x1071);
13816 IkReal x1077=((1.0)*x1071);
13817 IkReal x1078=(x1071*x1073);
13818 evalcond[0]=(gconst11+((new_r00*x1071))+((new_r10*x1072)));
13819 evalcond[1]=(x1076+x1075+new_r00);
13820 evalcond[2]=(gconst10+((new_r00*x1072))+(((-1.0)*new_r10*x1077)));
13821 evalcond[3]=((((-1.0)*new_r11*x1077))+gconst11+((new_r01*x1072)));
13822 evalcond[4]=(x1074+new_r01+(((-1.0)*x1078)));
13823 evalcond[5]=(x1074+new_r10+(((-1.0)*x1078)));
13824 evalcond[6]=(((new_r01*x1071))+((new_r11*x1072))+(((-1.0)*x1073)));
13825 evalcond[7]=((((-1.0)*x1076))+(((-1.0)*x1072*x1073))+new_r11);
13826 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
13827 {
13828 continue;
13829 }
13830 }
13831 
13832 {
13833 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13834 vinfos[0].jointtype = 1;
13835 vinfos[0].foffset = j0;
13836 vinfos[0].indices[0] = _ij0[0];
13837 vinfos[0].indices[1] = _ij0[1];
13838 vinfos[0].maxsolutions = _nj0;
13839 vinfos[1].jointtype = 1;
13840 vinfos[1].foffset = j1;
13841 vinfos[1].indices[0] = _ij1[0];
13842 vinfos[1].indices[1] = _ij1[1];
13843 vinfos[1].maxsolutions = _nj1;
13844 vinfos[2].jointtype = 1;
13845 vinfos[2].foffset = j2;
13846 vinfos[2].indices[0] = _ij2[0];
13847 vinfos[2].indices[1] = _ij2[1];
13848 vinfos[2].maxsolutions = _nj2;
13849 vinfos[3].jointtype = 1;
13850 vinfos[3].foffset = j3;
13851 vinfos[3].indices[0] = _ij3[0];
13852 vinfos[3].indices[1] = _ij3[1];
13853 vinfos[3].maxsolutions = _nj3;
13854 vinfos[4].jointtype = 1;
13855 vinfos[4].foffset = j4;
13856 vinfos[4].indices[0] = _ij4[0];
13857 vinfos[4].indices[1] = _ij4[1];
13858 vinfos[4].maxsolutions = _nj4;
13859 vinfos[5].jointtype = 1;
13860 vinfos[5].foffset = j5;
13861 vinfos[5].indices[0] = _ij5[0];
13862 vinfos[5].indices[1] = _ij5[1];
13863 vinfos[5].maxsolutions = _nj5;
13864 std::vector<int> vfree(0);
13865 solutions.AddSolution(vinfos,vfree);
13866 }
13867 }
13868 }
13869 
13870 }
13871 
13872 }
13873 
13874 }
13875 } while(0);
13876 if( bgotonextstatement )
13877 {
13878 bool bgotonextstatement = true;
13879 do
13880 {
13881 IkReal x1079=((-1.0)*new_r10);
13882 IkReal x1081 = ((new_r10*new_r10)+(new_r00*new_r00));
13883 if(IKabs(x1081)==0){
13884 continue;
13885 }
13886 IkReal x1080=pow(x1081,-0.5);
13887 CheckValue<IkReal> x1082 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(x1079),IKFAST_ATAN2_MAGTHRESH);
13888 if(!x1082.valid){
13889 continue;
13890 }
13891 IkReal gconst12=((-1.0)*(x1082.value));
13892 IkReal gconst13=(new_r00*x1080);
13893 IkReal gconst14=(x1079*x1080);
13894 CheckValue<IkReal> x1083 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
13895 if(!x1083.valid){
13896 continue;
13897 }
13898 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x1083.value)+j5)))), 6.28318530717959)));
13899 if( IKabs(evalcond[0]) < 0.0000050000000000 )
13900 {
13901 bgotonextstatement=false;
13902 {
13903 IkReal j3eval[3];
13904 IkReal x1084=((-1.0)*new_r10);
13905 CheckValue<IkReal> x1087 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(x1084),IKFAST_ATAN2_MAGTHRESH);
13906 if(!x1087.valid){
13907 continue;
13908 }
13909 IkReal x1085=((-1.0)*(x1087.value));
13910 IkReal x1086=x1080;
13911 sj4=0;
13912 cj4=-1.0;
13913 j4=3.14159265358979;
13914 sj5=gconst13;
13915 cj5=gconst14;
13916 j5=x1085;
13917 IkReal gconst12=x1085;
13918 IkReal gconst13=(new_r00*x1086);
13919 IkReal gconst14=(x1084*x1086);
13920 IkReal x1088=new_r10*new_r10;
13921 IkReal x1089=((1.0)*new_r00);
13922 IkReal x1090=((1.0)*new_r10*new_r11);
13923 IkReal x1091=((((-1.0)*x1090))+(((-1.0)*new_r01*x1089)));
13924 IkReal x1092=x1080;
13925 IkReal x1093=(new_r10*x1092);
13926 j3eval[0]=x1091;
13927 j3eval[1]=((IKabs((((x1088*x1092))+(((-1.0)*new_r01*x1093)))))+(IKabs(((((-1.0)*x1090*x1092))+(((-1.0)*x1089*x1093))))));
13928 j3eval[2]=IKsign(x1091);
13929 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
13930 {
13931 {
13932 IkReal j3eval[1];
13933 IkReal x1094=((-1.0)*new_r10);
13934 CheckValue<IkReal> x1097 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(x1094),IKFAST_ATAN2_MAGTHRESH);
13935 if(!x1097.valid){
13936 continue;
13937 }
13938 IkReal x1095=((-1.0)*(x1097.value));
13939 IkReal x1096=x1080;
13940 sj4=0;
13941 cj4=-1.0;
13942 j4=3.14159265358979;
13943 sj5=gconst13;
13944 cj5=gconst14;
13945 j5=x1095;
13946 IkReal gconst12=x1095;
13947 IkReal gconst13=(new_r00*x1096);
13948 IkReal gconst14=(x1094*x1096);
13949 IkReal x1098=new_r10*new_r10;
13950 CheckValue<IkReal> x1101=IKPowWithIntegerCheck((x1098+(new_r00*new_r00)),-1);
13951 if(!x1101.valid){
13952 continue;
13953 }
13954 IkReal x1099=x1101.value;
13955 IkReal x1100=(new_r00*x1099);
13956 j3eval[0]=((IKabs((((new_r00*new_r11))+((x1098*x1099)))))+(IKabs((((new_r01*x1098*x1100))+((new_r10*x1100))+((new_r01*x1100*(new_r00*new_r00)))))));
13957 if( IKabs(j3eval[0]) < 0.0000010000000000 )
13958 {
13959 {
13960 IkReal j3eval[1];
13961 IkReal x1102=((-1.0)*new_r10);
13962 CheckValue<IkReal> x1105 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(x1102),IKFAST_ATAN2_MAGTHRESH);
13963 if(!x1105.valid){
13964 continue;
13965 }
13966 IkReal x1103=((-1.0)*(x1105.value));
13967 IkReal x1104=x1080;
13968 sj4=0;
13969 cj4=-1.0;
13970 j4=3.14159265358979;
13971 sj5=gconst13;
13972 cj5=gconst14;
13973 j5=x1103;
13974 IkReal gconst12=x1103;
13975 IkReal gconst13=(new_r00*x1104);
13976 IkReal gconst14=(x1102*x1104);
13977 IkReal x1106=new_r10*new_r10;
13978 IkReal x1107=new_r00*new_r00;
13979 CheckValue<IkReal> x1111=IKPowWithIntegerCheck((x1106+x1107),-1);
13980 if(!x1111.valid){
13981 continue;
13982 }
13983 IkReal x1108=x1111.value;
13984 IkReal x1109=(new_r10*x1108);
13985 IkReal x1110=(x1106*x1108);
13986 j3eval[0]=((IKabs((x1110+(((-1.0)*x1108*(x1107*x1107)))+(((-1.0)*x1107*x1110)))))+(IKabs((((x1109*(new_r00*new_r00*new_r00)))+((new_r00*x1109))+((new_r00*x1109*(new_r10*new_r10)))))));
13987 if( IKabs(j3eval[0]) < 0.0000010000000000 )
13988 {
13989 {
13990 IkReal evalcond[2];
13991 bool bgotonextstatement = true;
13992 do
13993 {
13994 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
13995 if( IKabs(evalcond[0]) < 0.0000050000000000 )
13996 {
13997 bgotonextstatement=false;
13998 {
13999 IkReal j3eval[1];
14000 IkReal x1112=((-1.0)*new_r10);
14001 CheckValue<IkReal> x1114 = IKatan2WithCheck(IkReal(0),IkReal(x1112),IKFAST_ATAN2_MAGTHRESH);
14002 if(!x1114.valid){
14003 continue;
14004 }
14005 IkReal x1113=((-1.0)*(x1114.value));
14006 sj4=0;
14007 cj4=-1.0;
14008 j4=3.14159265358979;
14009 sj5=gconst13;
14010 cj5=gconst14;
14011 j5=x1113;
14012 new_r11=0;
14013 new_r00=0;
14014 IkReal gconst12=x1113;
14015 IkReal gconst13=0;
14016 IkReal x1115 = new_r10*new_r10;
14017 if(IKabs(x1115)==0){
14018 continue;
14019 }
14020 IkReal gconst14=(x1112*(pow(x1115,-0.5)));
14021 j3eval[0]=new_r01;
14022 if( IKabs(j3eval[0]) < 0.0000010000000000 )
14023 {
14024 {
14025 IkReal j3array[2], cj3array[2], sj3array[2];
14026 bool j3valid[2]={false};
14027 _nj3 = 2;
14028 CheckValue<IkReal> x1116=IKPowWithIntegerCheck(gconst14,-1);
14029 if(!x1116.valid){
14030 continue;
14031 }
14032 sj3array[0]=((-1.0)*new_r01*(x1116.value));
14033 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
14034 {
14035  j3valid[0] = j3valid[1] = true;
14036  j3array[0] = IKasin(sj3array[0]);
14037  cj3array[0] = IKcos(j3array[0]);
14038  sj3array[1] = sj3array[0];
14039  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
14040  cj3array[1] = -cj3array[0];
14041 }
14042 else if( isnan(sj3array[0]) )
14043 {
14044  // probably any value will work
14045  j3valid[0] = true;
14046  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
14047 }
14048 for(int ij3 = 0; ij3 < 2; ++ij3)
14049 {
14050 if( !j3valid[ij3] )
14051 {
14052  continue;
14053 }
14054 _ij3[0] = ij3; _ij3[1] = -1;
14055 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
14056 {
14057 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14058 {
14059  j3valid[iij3]=false; _ij3[1] = iij3; break;
14060 }
14061 }
14062 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14063 {
14064 IkReal evalcond[6];
14065 IkReal x1117=IKcos(j3);
14066 IkReal x1118=IKsin(j3);
14067 evalcond[0]=(new_r01*x1117);
14068 evalcond[1]=(gconst14*x1117);
14069 evalcond[2]=((-1.0)*new_r10*x1117);
14070 evalcond[3]=(gconst14+((new_r01*x1118)));
14071 evalcond[4]=(gconst14+((new_r10*x1118)));
14072 evalcond[5]=(((gconst14*x1118))+new_r10);
14073 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14074 {
14075 continue;
14076 }
14077 }
14078 
14079 {
14080 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14081 vinfos[0].jointtype = 1;
14082 vinfos[0].foffset = j0;
14083 vinfos[0].indices[0] = _ij0[0];
14084 vinfos[0].indices[1] = _ij0[1];
14085 vinfos[0].maxsolutions = _nj0;
14086 vinfos[1].jointtype = 1;
14087 vinfos[1].foffset = j1;
14088 vinfos[1].indices[0] = _ij1[0];
14089 vinfos[1].indices[1] = _ij1[1];
14090 vinfos[1].maxsolutions = _nj1;
14091 vinfos[2].jointtype = 1;
14092 vinfos[2].foffset = j2;
14093 vinfos[2].indices[0] = _ij2[0];
14094 vinfos[2].indices[1] = _ij2[1];
14095 vinfos[2].maxsolutions = _nj2;
14096 vinfos[3].jointtype = 1;
14097 vinfos[3].foffset = j3;
14098 vinfos[3].indices[0] = _ij3[0];
14099 vinfos[3].indices[1] = _ij3[1];
14100 vinfos[3].maxsolutions = _nj3;
14101 vinfos[4].jointtype = 1;
14102 vinfos[4].foffset = j4;
14103 vinfos[4].indices[0] = _ij4[0];
14104 vinfos[4].indices[1] = _ij4[1];
14105 vinfos[4].maxsolutions = _nj4;
14106 vinfos[5].jointtype = 1;
14107 vinfos[5].foffset = j5;
14108 vinfos[5].indices[0] = _ij5[0];
14109 vinfos[5].indices[1] = _ij5[1];
14110 vinfos[5].maxsolutions = _nj5;
14111 std::vector<int> vfree(0);
14112 solutions.AddSolution(vinfos,vfree);
14113 }
14114 }
14115 }
14116 
14117 } else
14118 {
14119 {
14120 IkReal j3array[2], cj3array[2], sj3array[2];
14121 bool j3valid[2]={false};
14122 _nj3 = 2;
14123 CheckValue<IkReal> x1119=IKPowWithIntegerCheck(new_r01,-1);
14124 if(!x1119.valid){
14125 continue;
14126 }
14127 sj3array[0]=((-1.0)*gconst14*(x1119.value));
14128 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
14129 {
14130  j3valid[0] = j3valid[1] = true;
14131  j3array[0] = IKasin(sj3array[0]);
14132  cj3array[0] = IKcos(j3array[0]);
14133  sj3array[1] = sj3array[0];
14134  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
14135  cj3array[1] = -cj3array[0];
14136 }
14137 else if( isnan(sj3array[0]) )
14138 {
14139  // probably any value will work
14140  j3valid[0] = true;
14141  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
14142 }
14143 for(int ij3 = 0; ij3 < 2; ++ij3)
14144 {
14145 if( !j3valid[ij3] )
14146 {
14147  continue;
14148 }
14149 _ij3[0] = ij3; _ij3[1] = -1;
14150 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
14151 {
14152 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14153 {
14154  j3valid[iij3]=false; _ij3[1] = iij3; break;
14155 }
14156 }
14157 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14158 {
14159 IkReal evalcond[6];
14160 IkReal x1120=IKcos(j3);
14161 IkReal x1121=IKsin(j3);
14162 IkReal x1122=(gconst14*x1121);
14163 evalcond[0]=(new_r01*x1120);
14164 evalcond[1]=(gconst14*x1120);
14165 evalcond[2]=((-1.0)*new_r10*x1120);
14166 evalcond[3]=(x1122+new_r01);
14167 evalcond[4]=(gconst14+((new_r10*x1121)));
14168 evalcond[5]=(x1122+new_r10);
14169 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14170 {
14171 continue;
14172 }
14173 }
14174 
14175 {
14176 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14177 vinfos[0].jointtype = 1;
14178 vinfos[0].foffset = j0;
14179 vinfos[0].indices[0] = _ij0[0];
14180 vinfos[0].indices[1] = _ij0[1];
14181 vinfos[0].maxsolutions = _nj0;
14182 vinfos[1].jointtype = 1;
14183 vinfos[1].foffset = j1;
14184 vinfos[1].indices[0] = _ij1[0];
14185 vinfos[1].indices[1] = _ij1[1];
14186 vinfos[1].maxsolutions = _nj1;
14187 vinfos[2].jointtype = 1;
14188 vinfos[2].foffset = j2;
14189 vinfos[2].indices[0] = _ij2[0];
14190 vinfos[2].indices[1] = _ij2[1];
14191 vinfos[2].maxsolutions = _nj2;
14192 vinfos[3].jointtype = 1;
14193 vinfos[3].foffset = j3;
14194 vinfos[3].indices[0] = _ij3[0];
14195 vinfos[3].indices[1] = _ij3[1];
14196 vinfos[3].maxsolutions = _nj3;
14197 vinfos[4].jointtype = 1;
14198 vinfos[4].foffset = j4;
14199 vinfos[4].indices[0] = _ij4[0];
14200 vinfos[4].indices[1] = _ij4[1];
14201 vinfos[4].maxsolutions = _nj4;
14202 vinfos[5].jointtype = 1;
14203 vinfos[5].foffset = j5;
14204 vinfos[5].indices[0] = _ij5[0];
14205 vinfos[5].indices[1] = _ij5[1];
14206 vinfos[5].maxsolutions = _nj5;
14207 std::vector<int> vfree(0);
14208 solutions.AddSolution(vinfos,vfree);
14209 }
14210 }
14211 }
14212 
14213 }
14214 
14215 }
14216 
14217 }
14218 } while(0);
14219 if( bgotonextstatement )
14220 {
14221 bool bgotonextstatement = true;
14222 do
14223 {
14224 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
14225 evalcond[1]=gconst14;
14226 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
14227 {
14228 bgotonextstatement=false;
14229 {
14230 IkReal j3eval[3];
14231 IkReal x1123=((-1.0)*new_r10);
14232 CheckValue<IkReal> x1125 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(x1123),IKFAST_ATAN2_MAGTHRESH);
14233 if(!x1125.valid){
14234 continue;
14235 }
14236 IkReal x1124=((-1.0)*(x1125.value));
14237 sj4=0;
14238 cj4=-1.0;
14239 j4=3.14159265358979;
14240 sj5=gconst13;
14241 cj5=gconst14;
14242 j5=x1124;
14243 new_r11=0;
14244 new_r01=0;
14245 new_r22=0;
14246 new_r20=0;
14247 IkReal gconst12=x1124;
14248 IkReal gconst13=new_r00;
14249 IkReal gconst14=x1123;
14250 j3eval[0]=-1.0;
14251 j3eval[1]=-1.0;
14252 j3eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10))));
14253 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
14254 {
14255 {
14256 IkReal j3eval[3];
14257 IkReal x1126=((-1.0)*new_r10);
14258 CheckValue<IkReal> x1128 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(x1126),IKFAST_ATAN2_MAGTHRESH);
14259 if(!x1128.valid){
14260 continue;
14261 }
14262 IkReal x1127=((-1.0)*(x1128.value));
14263 sj4=0;
14264 cj4=-1.0;
14265 j4=3.14159265358979;
14266 sj5=gconst13;
14267 cj5=gconst14;
14268 j5=x1127;
14269 new_r11=0;
14270 new_r01=0;
14271 new_r22=0;
14272 new_r20=0;
14273 IkReal gconst12=x1127;
14274 IkReal gconst13=new_r00;
14275 IkReal gconst14=x1126;
14276 j3eval[0]=-1.0;
14277 j3eval[1]=-1.0;
14278 j3eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10))));
14279 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
14280 {
14281 {
14282 IkReal j3eval[3];
14283 IkReal x1129=((-1.0)*new_r10);
14284 CheckValue<IkReal> x1131 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(x1129),IKFAST_ATAN2_MAGTHRESH);
14285 if(!x1131.valid){
14286 continue;
14287 }
14288 IkReal x1130=((-1.0)*(x1131.value));
14289 sj4=0;
14290 cj4=-1.0;
14291 j4=3.14159265358979;
14292 sj5=gconst13;
14293 cj5=gconst14;
14294 j5=x1130;
14295 new_r11=0;
14296 new_r01=0;
14297 new_r22=0;
14298 new_r20=0;
14299 IkReal gconst12=x1130;
14300 IkReal gconst13=new_r00;
14301 IkReal gconst14=x1129;
14302 j3eval[0]=1.0;
14303 j3eval[1]=1.0;
14304 j3eval[2]=((((0.5)*(IKabs(((-1.0)+(((2.0)*(new_r10*new_r10))))))))+(IKabs((new_r00*new_r10))));
14305 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
14306 {
14307 continue; // 3 cases reached
14308 
14309 } else
14310 {
14311 {
14312 IkReal j3array[1], cj3array[1], sj3array[1];
14313 bool j3valid[1]={false};
14314 _nj3 = 1;
14315 IkReal x1132=((1.0)*gconst14);
14316 CheckValue<IkReal> x1133=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x1132))+((gconst13*new_r00)))),-1);
14317 if(!x1133.valid){
14318 continue;
14319 }
14320 CheckValue<IkReal> x1134 = IKatan2WithCheck(IkReal(((gconst14*gconst14)+(((-1.0)*(new_r00*new_r00))))),IkReal(((((-1.0)*gconst13*x1132))+((new_r00*new_r10)))),IKFAST_ATAN2_MAGTHRESH);
14321 if(!x1134.valid){
14322 continue;
14323 }
14324 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1133.value)))+(x1134.value));
14325 sj3array[0]=IKsin(j3array[0]);
14326 cj3array[0]=IKcos(j3array[0]);
14327 if( j3array[0] > IKPI )
14328 {
14329  j3array[0]-=IK2PI;
14330 }
14331 else if( j3array[0] < -IKPI )
14332 { j3array[0]+=IK2PI;
14333 }
14334 j3valid[0] = true;
14335 for(int ij3 = 0; ij3 < 1; ++ij3)
14336 {
14337 if( !j3valid[ij3] )
14338 {
14339  continue;
14340 }
14341 _ij3[0] = ij3; _ij3[1] = -1;
14342 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14343 {
14344 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14345 {
14346  j3valid[iij3]=false; _ij3[1] = iij3; break;
14347 }
14348 }
14349 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14350 {
14351 IkReal evalcond[6];
14352 IkReal x1135=IKsin(j3);
14353 IkReal x1136=IKcos(j3);
14354 IkReal x1137=((1.0)*gconst13);
14355 IkReal x1138=(gconst14*x1135);
14356 IkReal x1139=(gconst14*x1136);
14357 IkReal x1140=(x1136*x1137);
14358 evalcond[0]=(x1138+(((-1.0)*x1140)));
14359 evalcond[1]=(gconst14+((new_r00*x1136))+((new_r10*x1135)));
14360 evalcond[2]=(x1139+((gconst13*x1135))+new_r00);
14361 evalcond[3]=(gconst13+((new_r00*x1135))+(((-1.0)*new_r10*x1136)));
14362 evalcond[4]=((((-1.0)*x1139))+(((-1.0)*x1135*x1137)));
14363 evalcond[5]=(x1138+(((-1.0)*x1140))+new_r10);
14364 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14365 {
14366 continue;
14367 }
14368 }
14369 
14370 {
14371 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14372 vinfos[0].jointtype = 1;
14373 vinfos[0].foffset = j0;
14374 vinfos[0].indices[0] = _ij0[0];
14375 vinfos[0].indices[1] = _ij0[1];
14376 vinfos[0].maxsolutions = _nj0;
14377 vinfos[1].jointtype = 1;
14378 vinfos[1].foffset = j1;
14379 vinfos[1].indices[0] = _ij1[0];
14380 vinfos[1].indices[1] = _ij1[1];
14381 vinfos[1].maxsolutions = _nj1;
14382 vinfos[2].jointtype = 1;
14383 vinfos[2].foffset = j2;
14384 vinfos[2].indices[0] = _ij2[0];
14385 vinfos[2].indices[1] = _ij2[1];
14386 vinfos[2].maxsolutions = _nj2;
14387 vinfos[3].jointtype = 1;
14388 vinfos[3].foffset = j3;
14389 vinfos[3].indices[0] = _ij3[0];
14390 vinfos[3].indices[1] = _ij3[1];
14391 vinfos[3].maxsolutions = _nj3;
14392 vinfos[4].jointtype = 1;
14393 vinfos[4].foffset = j4;
14394 vinfos[4].indices[0] = _ij4[0];
14395 vinfos[4].indices[1] = _ij4[1];
14396 vinfos[4].maxsolutions = _nj4;
14397 vinfos[5].jointtype = 1;
14398 vinfos[5].foffset = j5;
14399 vinfos[5].indices[0] = _ij5[0];
14400 vinfos[5].indices[1] = _ij5[1];
14401 vinfos[5].maxsolutions = _nj5;
14402 std::vector<int> vfree(0);
14403 solutions.AddSolution(vinfos,vfree);
14404 }
14405 }
14406 }
14407 
14408 }
14409 
14410 }
14411 
14412 } else
14413 {
14414 {
14415 IkReal j3array[1], cj3array[1], sj3array[1];
14416 bool j3valid[1]={false};
14417 _nj3 = 1;
14418 CheckValue<IkReal> x1141=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst14*gconst14)))+(((-1.0)*(gconst13*gconst13))))),-1);
14419 if(!x1141.valid){
14420 continue;
14421 }
14422 CheckValue<IkReal> x1142 = IKatan2WithCheck(IkReal((gconst13*new_r00)),IkReal((gconst14*new_r00)),IKFAST_ATAN2_MAGTHRESH);
14423 if(!x1142.valid){
14424 continue;
14425 }
14426 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1141.value)))+(x1142.value));
14427 sj3array[0]=IKsin(j3array[0]);
14428 cj3array[0]=IKcos(j3array[0]);
14429 if( j3array[0] > IKPI )
14430 {
14431  j3array[0]-=IK2PI;
14432 }
14433 else if( j3array[0] < -IKPI )
14434 { j3array[0]+=IK2PI;
14435 }
14436 j3valid[0] = true;
14437 for(int ij3 = 0; ij3 < 1; ++ij3)
14438 {
14439 if( !j3valid[ij3] )
14440 {
14441  continue;
14442 }
14443 _ij3[0] = ij3; _ij3[1] = -1;
14444 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14445 {
14446 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14447 {
14448  j3valid[iij3]=false; _ij3[1] = iij3; break;
14449 }
14450 }
14451 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14452 {
14453 IkReal evalcond[6];
14454 IkReal x1143=IKsin(j3);
14455 IkReal x1144=IKcos(j3);
14456 IkReal x1145=((1.0)*gconst13);
14457 IkReal x1146=(gconst14*x1143);
14458 IkReal x1147=(gconst14*x1144);
14459 IkReal x1148=(x1144*x1145);
14460 evalcond[0]=(x1146+(((-1.0)*x1148)));
14461 evalcond[1]=(((new_r00*x1144))+gconst14+((new_r10*x1143)));
14462 evalcond[2]=(x1147+((gconst13*x1143))+new_r00);
14463 evalcond[3]=((((-1.0)*new_r10*x1144))+((new_r00*x1143))+gconst13);
14464 evalcond[4]=((((-1.0)*x1143*x1145))+(((-1.0)*x1147)));
14465 evalcond[5]=(x1146+(((-1.0)*x1148))+new_r10);
14466 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14467 {
14468 continue;
14469 }
14470 }
14471 
14472 {
14473 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14474 vinfos[0].jointtype = 1;
14475 vinfos[0].foffset = j0;
14476 vinfos[0].indices[0] = _ij0[0];
14477 vinfos[0].indices[1] = _ij0[1];
14478 vinfos[0].maxsolutions = _nj0;
14479 vinfos[1].jointtype = 1;
14480 vinfos[1].foffset = j1;
14481 vinfos[1].indices[0] = _ij1[0];
14482 vinfos[1].indices[1] = _ij1[1];
14483 vinfos[1].maxsolutions = _nj1;
14484 vinfos[2].jointtype = 1;
14485 vinfos[2].foffset = j2;
14486 vinfos[2].indices[0] = _ij2[0];
14487 vinfos[2].indices[1] = _ij2[1];
14488 vinfos[2].maxsolutions = _nj2;
14489 vinfos[3].jointtype = 1;
14490 vinfos[3].foffset = j3;
14491 vinfos[3].indices[0] = _ij3[0];
14492 vinfos[3].indices[1] = _ij3[1];
14493 vinfos[3].maxsolutions = _nj3;
14494 vinfos[4].jointtype = 1;
14495 vinfos[4].foffset = j4;
14496 vinfos[4].indices[0] = _ij4[0];
14497 vinfos[4].indices[1] = _ij4[1];
14498 vinfos[4].maxsolutions = _nj4;
14499 vinfos[5].jointtype = 1;
14500 vinfos[5].foffset = j5;
14501 vinfos[5].indices[0] = _ij5[0];
14502 vinfos[5].indices[1] = _ij5[1];
14503 vinfos[5].maxsolutions = _nj5;
14504 std::vector<int> vfree(0);
14505 solutions.AddSolution(vinfos,vfree);
14506 }
14507 }
14508 }
14509 
14510 }
14511 
14512 }
14513 
14514 } else
14515 {
14516 {
14517 IkReal j3array[1], cj3array[1], sj3array[1];
14518 bool j3valid[1]={false};
14519 _nj3 = 1;
14520 CheckValue<IkReal> x1149 = IKatan2WithCheck(IkReal(gconst13*gconst13),IkReal((gconst13*gconst14)),IKFAST_ATAN2_MAGTHRESH);
14521 if(!x1149.valid){
14522 continue;
14523 }
14524 CheckValue<IkReal> x1150=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst13*new_r00))+((gconst14*new_r10)))),-1);
14525 if(!x1150.valid){
14526 continue;
14527 }
14528 j3array[0]=((-1.5707963267949)+(x1149.value)+(((1.5707963267949)*(x1150.value))));
14529 sj3array[0]=IKsin(j3array[0]);
14530 cj3array[0]=IKcos(j3array[0]);
14531 if( j3array[0] > IKPI )
14532 {
14533  j3array[0]-=IK2PI;
14534 }
14535 else if( j3array[0] < -IKPI )
14536 { j3array[0]+=IK2PI;
14537 }
14538 j3valid[0] = true;
14539 for(int ij3 = 0; ij3 < 1; ++ij3)
14540 {
14541 if( !j3valid[ij3] )
14542 {
14543  continue;
14544 }
14545 _ij3[0] = ij3; _ij3[1] = -1;
14546 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14547 {
14548 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14549 {
14550  j3valid[iij3]=false; _ij3[1] = iij3; break;
14551 }
14552 }
14553 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14554 {
14555 IkReal evalcond[6];
14556 IkReal x1151=IKsin(j3);
14557 IkReal x1152=IKcos(j3);
14558 IkReal x1153=((1.0)*gconst13);
14559 IkReal x1154=(gconst14*x1151);
14560 IkReal x1155=(gconst14*x1152);
14561 IkReal x1156=(x1152*x1153);
14562 evalcond[0]=(x1154+(((-1.0)*x1156)));
14563 evalcond[1]=(((new_r10*x1151))+gconst14+((new_r00*x1152)));
14564 evalcond[2]=(x1155+((gconst13*x1151))+new_r00);
14565 evalcond[3]=(gconst13+((new_r00*x1151))+(((-1.0)*new_r10*x1152)));
14566 evalcond[4]=((((-1.0)*x1155))+(((-1.0)*x1151*x1153)));
14567 evalcond[5]=(x1154+(((-1.0)*x1156))+new_r10);
14568 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14569 {
14570 continue;
14571 }
14572 }
14573 
14574 {
14575 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14576 vinfos[0].jointtype = 1;
14577 vinfos[0].foffset = j0;
14578 vinfos[0].indices[0] = _ij0[0];
14579 vinfos[0].indices[1] = _ij0[1];
14580 vinfos[0].maxsolutions = _nj0;
14581 vinfos[1].jointtype = 1;
14582 vinfos[1].foffset = j1;
14583 vinfos[1].indices[0] = _ij1[0];
14584 vinfos[1].indices[1] = _ij1[1];
14585 vinfos[1].maxsolutions = _nj1;
14586 vinfos[2].jointtype = 1;
14587 vinfos[2].foffset = j2;
14588 vinfos[2].indices[0] = _ij2[0];
14589 vinfos[2].indices[1] = _ij2[1];
14590 vinfos[2].maxsolutions = _nj2;
14591 vinfos[3].jointtype = 1;
14592 vinfos[3].foffset = j3;
14593 vinfos[3].indices[0] = _ij3[0];
14594 vinfos[3].indices[1] = _ij3[1];
14595 vinfos[3].maxsolutions = _nj3;
14596 vinfos[4].jointtype = 1;
14597 vinfos[4].foffset = j4;
14598 vinfos[4].indices[0] = _ij4[0];
14599 vinfos[4].indices[1] = _ij4[1];
14600 vinfos[4].maxsolutions = _nj4;
14601 vinfos[5].jointtype = 1;
14602 vinfos[5].foffset = j5;
14603 vinfos[5].indices[0] = _ij5[0];
14604 vinfos[5].indices[1] = _ij5[1];
14605 vinfos[5].maxsolutions = _nj5;
14606 std::vector<int> vfree(0);
14607 solutions.AddSolution(vinfos,vfree);
14608 }
14609 }
14610 }
14611 
14612 }
14613 
14614 }
14615 
14616 }
14617 } while(0);
14618 if( bgotonextstatement )
14619 {
14620 bool bgotonextstatement = true;
14621 do
14622 {
14623 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
14624 if( IKabs(evalcond[0]) < 0.0000050000000000 )
14625 {
14626 bgotonextstatement=false;
14627 {
14628 IkReal j3array[2], cj3array[2], sj3array[2];
14629 bool j3valid[2]={false};
14630 _nj3 = 2;
14631 CheckValue<IkReal> x1157=IKPowWithIntegerCheck(gconst13,-1);
14632 if(!x1157.valid){
14633 continue;
14634 }
14635 sj3array[0]=(new_r11*(x1157.value));
14636 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
14637 {
14638  j3valid[0] = j3valid[1] = true;
14639  j3array[0] = IKasin(sj3array[0]);
14640  cj3array[0] = IKcos(j3array[0]);
14641  sj3array[1] = sj3array[0];
14642  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
14643  cj3array[1] = -cj3array[0];
14644 }
14645 else if( isnan(sj3array[0]) )
14646 {
14647  // probably any value will work
14648  j3valid[0] = true;
14649  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
14650 }
14651 for(int ij3 = 0; ij3 < 2; ++ij3)
14652 {
14653 if( !j3valid[ij3] )
14654 {
14655  continue;
14656 }
14657 _ij3[0] = ij3; _ij3[1] = -1;
14658 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
14659 {
14660 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14661 {
14662  j3valid[iij3]=false; _ij3[1] = iij3; break;
14663 }
14664 }
14665 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14666 {
14667 IkReal evalcond[6];
14668 IkReal x1158=IKcos(j3);
14669 IkReal x1159=IKsin(j3);
14670 IkReal x1160=((-1.0)*x1158);
14671 evalcond[0]=(new_r00*x1158);
14672 evalcond[1]=(new_r11*x1160);
14673 evalcond[2]=(gconst13*x1160);
14674 evalcond[3]=(gconst13+((new_r00*x1159)));
14675 evalcond[4]=(((gconst13*x1159))+new_r00);
14676 evalcond[5]=(((new_r11*x1159))+(((-1.0)*gconst13)));
14677 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14678 {
14679 continue;
14680 }
14681 }
14682 
14683 {
14684 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14685 vinfos[0].jointtype = 1;
14686 vinfos[0].foffset = j0;
14687 vinfos[0].indices[0] = _ij0[0];
14688 vinfos[0].indices[1] = _ij0[1];
14689 vinfos[0].maxsolutions = _nj0;
14690 vinfos[1].jointtype = 1;
14691 vinfos[1].foffset = j1;
14692 vinfos[1].indices[0] = _ij1[0];
14693 vinfos[1].indices[1] = _ij1[1];
14694 vinfos[1].maxsolutions = _nj1;
14695 vinfos[2].jointtype = 1;
14696 vinfos[2].foffset = j2;
14697 vinfos[2].indices[0] = _ij2[0];
14698 vinfos[2].indices[1] = _ij2[1];
14699 vinfos[2].maxsolutions = _nj2;
14700 vinfos[3].jointtype = 1;
14701 vinfos[3].foffset = j3;
14702 vinfos[3].indices[0] = _ij3[0];
14703 vinfos[3].indices[1] = _ij3[1];
14704 vinfos[3].maxsolutions = _nj3;
14705 vinfos[4].jointtype = 1;
14706 vinfos[4].foffset = j4;
14707 vinfos[4].indices[0] = _ij4[0];
14708 vinfos[4].indices[1] = _ij4[1];
14709 vinfos[4].maxsolutions = _nj4;
14710 vinfos[5].jointtype = 1;
14711 vinfos[5].foffset = j5;
14712 vinfos[5].indices[0] = _ij5[0];
14713 vinfos[5].indices[1] = _ij5[1];
14714 vinfos[5].maxsolutions = _nj5;
14715 std::vector<int> vfree(0);
14716 solutions.AddSolution(vinfos,vfree);
14717 }
14718 }
14719 }
14720 
14721 }
14722 } while(0);
14723 if( bgotonextstatement )
14724 {
14725 bool bgotonextstatement = true;
14726 do
14727 {
14728 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
14729 if( IKabs(evalcond[0]) < 0.0000050000000000 )
14730 {
14731 bgotonextstatement=false;
14732 {
14733 IkReal j3eval[1];
14734 CheckValue<IkReal> x1162 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
14735 if(!x1162.valid){
14736 continue;
14737 }
14738 IkReal x1161=((-1.0)*(x1162.value));
14739 sj4=0;
14740 cj4=-1.0;
14741 j4=3.14159265358979;
14742 sj5=gconst13;
14743 cj5=gconst14;
14744 j5=x1161;
14745 new_r11=0;
14746 new_r10=0;
14747 new_r22=0;
14748 new_r02=0;
14749 IkReal gconst12=x1161;
14750 IkReal x1163 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
14751 if(IKabs(x1163)==0){
14752 continue;
14753 }
14754 IkReal gconst13=(new_r00*(pow(x1163,-0.5)));
14755 IkReal gconst14=0;
14756 j3eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
14757 if( IKabs(j3eval[0]) < 0.0000010000000000 )
14758 {
14759 {
14760 IkReal j3eval[1];
14761 CheckValue<IkReal> x1165 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
14762 if(!x1165.valid){
14763 continue;
14764 }
14765 IkReal x1164=((-1.0)*(x1165.value));
14766 sj4=0;
14767 cj4=-1.0;
14768 j4=3.14159265358979;
14769 sj5=gconst13;
14770 cj5=gconst14;
14771 j5=x1164;
14772 new_r11=0;
14773 new_r10=0;
14774 new_r22=0;
14775 new_r02=0;
14776 IkReal gconst12=x1164;
14777 IkReal x1166 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
14778 if(IKabs(x1166)==0){
14779 continue;
14780 }
14781 IkReal gconst13=(new_r00*(pow(x1166,-0.5)));
14782 IkReal gconst14=0;
14783 j3eval[0]=new_r00;
14784 if( IKabs(j3eval[0]) < 0.0000010000000000 )
14785 {
14786 {
14787 IkReal j3eval[2];
14788 CheckValue<IkReal> x1168 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
14789 if(!x1168.valid){
14790 continue;
14791 }
14792 IkReal x1167=((-1.0)*(x1168.value));
14793 sj4=0;
14794 cj4=-1.0;
14795 j4=3.14159265358979;
14796 sj5=gconst13;
14797 cj5=gconst14;
14798 j5=x1167;
14799 new_r11=0;
14800 new_r10=0;
14801 new_r22=0;
14802 new_r02=0;
14803 IkReal gconst12=x1167;
14804 IkReal x1169 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
14805 if(IKabs(x1169)==0){
14806 continue;
14807 }
14808 IkReal gconst13=(new_r00*(pow(x1169,-0.5)));
14809 IkReal gconst14=0;
14810 j3eval[0]=new_r00;
14811 j3eval[1]=new_r01;
14812 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
14813 {
14814 continue; // 3 cases reached
14815 
14816 } else
14817 {
14818 {
14819 IkReal j3array[1], cj3array[1], sj3array[1];
14820 bool j3valid[1]={false};
14821 _nj3 = 1;
14822 CheckValue<IkReal> x1170=IKPowWithIntegerCheck(new_r00,-1);
14823 if(!x1170.valid){
14824 continue;
14825 }
14826 CheckValue<IkReal> x1171=IKPowWithIntegerCheck(new_r01,-1);
14827 if(!x1171.valid){
14828 continue;
14829 }
14830 if( IKabs(((-1.0)*gconst13*(x1170.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst13*(x1171.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst13*(x1170.value)))+IKsqr((gconst13*(x1171.value)))-1) <= IKFAST_SINCOS_THRESH )
14831  continue;
14832 j3array[0]=IKatan2(((-1.0)*gconst13*(x1170.value)), (gconst13*(x1171.value)));
14833 sj3array[0]=IKsin(j3array[0]);
14834 cj3array[0]=IKcos(j3array[0]);
14835 if( j3array[0] > IKPI )
14836 {
14837  j3array[0]-=IK2PI;
14838 }
14839 else if( j3array[0] < -IKPI )
14840 { j3array[0]+=IK2PI;
14841 }
14842 j3valid[0] = true;
14843 for(int ij3 = 0; ij3 < 1; ++ij3)
14844 {
14845 if( !j3valid[ij3] )
14846 {
14847  continue;
14848 }
14849 _ij3[0] = ij3; _ij3[1] = -1;
14850 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14851 {
14852 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14853 {
14854  j3valid[iij3]=false; _ij3[1] = iij3; break;
14855 }
14856 }
14857 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14858 {
14859 IkReal evalcond[8];
14860 IkReal x1172=IKsin(j3);
14861 IkReal x1173=IKcos(j3);
14862 IkReal x1174=(gconst13*x1173);
14863 IkReal x1175=(gconst13*x1172);
14864 evalcond[0]=(new_r01*x1172);
14865 evalcond[1]=(new_r00*x1173);
14866 evalcond[2]=((-1.0)*x1175);
14867 evalcond[3]=((-1.0)*x1174);
14868 evalcond[4]=(gconst13+((new_r00*x1172)));
14869 evalcond[5]=(x1175+new_r00);
14870 evalcond[6]=(new_r01+(((-1.0)*x1174)));
14871 evalcond[7]=((((-1.0)*gconst13))+((new_r01*x1173)));
14872 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
14873 {
14874 continue;
14875 }
14876 }
14877 
14878 {
14879 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14880 vinfos[0].jointtype = 1;
14881 vinfos[0].foffset = j0;
14882 vinfos[0].indices[0] = _ij0[0];
14883 vinfos[0].indices[1] = _ij0[1];
14884 vinfos[0].maxsolutions = _nj0;
14885 vinfos[1].jointtype = 1;
14886 vinfos[1].foffset = j1;
14887 vinfos[1].indices[0] = _ij1[0];
14888 vinfos[1].indices[1] = _ij1[1];
14889 vinfos[1].maxsolutions = _nj1;
14890 vinfos[2].jointtype = 1;
14891 vinfos[2].foffset = j2;
14892 vinfos[2].indices[0] = _ij2[0];
14893 vinfos[2].indices[1] = _ij2[1];
14894 vinfos[2].maxsolutions = _nj2;
14895 vinfos[3].jointtype = 1;
14896 vinfos[3].foffset = j3;
14897 vinfos[3].indices[0] = _ij3[0];
14898 vinfos[3].indices[1] = _ij3[1];
14899 vinfos[3].maxsolutions = _nj3;
14900 vinfos[4].jointtype = 1;
14901 vinfos[4].foffset = j4;
14902 vinfos[4].indices[0] = _ij4[0];
14903 vinfos[4].indices[1] = _ij4[1];
14904 vinfos[4].maxsolutions = _nj4;
14905 vinfos[5].jointtype = 1;
14906 vinfos[5].foffset = j5;
14907 vinfos[5].indices[0] = _ij5[0];
14908 vinfos[5].indices[1] = _ij5[1];
14909 vinfos[5].maxsolutions = _nj5;
14910 std::vector<int> vfree(0);
14911 solutions.AddSolution(vinfos,vfree);
14912 }
14913 }
14914 }
14915 
14916 }
14917 
14918 }
14919 
14920 } else
14921 {
14922 {
14923 IkReal j3array[1], cj3array[1], sj3array[1];
14924 bool j3valid[1]={false};
14925 _nj3 = 1;
14926 CheckValue<IkReal> x1176=IKPowWithIntegerCheck(new_r00,-1);
14927 if(!x1176.valid){
14928 continue;
14929 }
14930 CheckValue<IkReal> x1177=IKPowWithIntegerCheck(gconst13,-1);
14931 if(!x1177.valid){
14932 continue;
14933 }
14934 if( IKabs(((-1.0)*gconst13*(x1176.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1177.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst13*(x1176.value)))+IKsqr((new_r01*(x1177.value)))-1) <= IKFAST_SINCOS_THRESH )
14935  continue;
14936 j3array[0]=IKatan2(((-1.0)*gconst13*(x1176.value)), (new_r01*(x1177.value)));
14937 sj3array[0]=IKsin(j3array[0]);
14938 cj3array[0]=IKcos(j3array[0]);
14939 if( j3array[0] > IKPI )
14940 {
14941  j3array[0]-=IK2PI;
14942 }
14943 else if( j3array[0] < -IKPI )
14944 { j3array[0]+=IK2PI;
14945 }
14946 j3valid[0] = true;
14947 for(int ij3 = 0; ij3 < 1; ++ij3)
14948 {
14949 if( !j3valid[ij3] )
14950 {
14951  continue;
14952 }
14953 _ij3[0] = ij3; _ij3[1] = -1;
14954 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14955 {
14956 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14957 {
14958  j3valid[iij3]=false; _ij3[1] = iij3; break;
14959 }
14960 }
14961 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14962 {
14963 IkReal evalcond[8];
14964 IkReal x1178=IKsin(j3);
14965 IkReal x1179=IKcos(j3);
14966 IkReal x1180=(gconst13*x1179);
14967 IkReal x1181=(gconst13*x1178);
14968 evalcond[0]=(new_r01*x1178);
14969 evalcond[1]=(new_r00*x1179);
14970 evalcond[2]=((-1.0)*x1181);
14971 evalcond[3]=((-1.0)*x1180);
14972 evalcond[4]=(gconst13+((new_r00*x1178)));
14973 evalcond[5]=(x1181+new_r00);
14974 evalcond[6]=(new_r01+(((-1.0)*x1180)));
14975 evalcond[7]=((((-1.0)*gconst13))+((new_r01*x1179)));
14976 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
14977 {
14978 continue;
14979 }
14980 }
14981 
14982 {
14983 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14984 vinfos[0].jointtype = 1;
14985 vinfos[0].foffset = j0;
14986 vinfos[0].indices[0] = _ij0[0];
14987 vinfos[0].indices[1] = _ij0[1];
14988 vinfos[0].maxsolutions = _nj0;
14989 vinfos[1].jointtype = 1;
14990 vinfos[1].foffset = j1;
14991 vinfos[1].indices[0] = _ij1[0];
14992 vinfos[1].indices[1] = _ij1[1];
14993 vinfos[1].maxsolutions = _nj1;
14994 vinfos[2].jointtype = 1;
14995 vinfos[2].foffset = j2;
14996 vinfos[2].indices[0] = _ij2[0];
14997 vinfos[2].indices[1] = _ij2[1];
14998 vinfos[2].maxsolutions = _nj2;
14999 vinfos[3].jointtype = 1;
15000 vinfos[3].foffset = j3;
15001 vinfos[3].indices[0] = _ij3[0];
15002 vinfos[3].indices[1] = _ij3[1];
15003 vinfos[3].maxsolutions = _nj3;
15004 vinfos[4].jointtype = 1;
15005 vinfos[4].foffset = j4;
15006 vinfos[4].indices[0] = _ij4[0];
15007 vinfos[4].indices[1] = _ij4[1];
15008 vinfos[4].maxsolutions = _nj4;
15009 vinfos[5].jointtype = 1;
15010 vinfos[5].foffset = j5;
15011 vinfos[5].indices[0] = _ij5[0];
15012 vinfos[5].indices[1] = _ij5[1];
15013 vinfos[5].maxsolutions = _nj5;
15014 std::vector<int> vfree(0);
15015 solutions.AddSolution(vinfos,vfree);
15016 }
15017 }
15018 }
15019 
15020 }
15021 
15022 }
15023 
15024 } else
15025 {
15026 {
15027 IkReal j3array[1], cj3array[1], sj3array[1];
15028 bool j3valid[1]={false};
15029 _nj3 = 1;
15030 CheckValue<IkReal> x1182 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
15031 if(!x1182.valid){
15032 continue;
15033 }
15034 CheckValue<IkReal> x1183=IKPowWithIntegerCheck(IKsign(gconst13),-1);
15035 if(!x1183.valid){
15036 continue;
15037 }
15038 j3array[0]=((-1.5707963267949)+(x1182.value)+(((1.5707963267949)*(x1183.value))));
15039 sj3array[0]=IKsin(j3array[0]);
15040 cj3array[0]=IKcos(j3array[0]);
15041 if( j3array[0] > IKPI )
15042 {
15043  j3array[0]-=IK2PI;
15044 }
15045 else if( j3array[0] < -IKPI )
15046 { j3array[0]+=IK2PI;
15047 }
15048 j3valid[0] = true;
15049 for(int ij3 = 0; ij3 < 1; ++ij3)
15050 {
15051 if( !j3valid[ij3] )
15052 {
15053  continue;
15054 }
15055 _ij3[0] = ij3; _ij3[1] = -1;
15056 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15057 {
15058 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15059 {
15060  j3valid[iij3]=false; _ij3[1] = iij3; break;
15061 }
15062 }
15063 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15064 {
15065 IkReal evalcond[8];
15066 IkReal x1184=IKsin(j3);
15067 IkReal x1185=IKcos(j3);
15068 IkReal x1186=(gconst13*x1185);
15069 IkReal x1187=(gconst13*x1184);
15070 evalcond[0]=(new_r01*x1184);
15071 evalcond[1]=(new_r00*x1185);
15072 evalcond[2]=((-1.0)*x1187);
15073 evalcond[3]=((-1.0)*x1186);
15074 evalcond[4]=(gconst13+((new_r00*x1184)));
15075 evalcond[5]=(x1187+new_r00);
15076 evalcond[6]=(new_r01+(((-1.0)*x1186)));
15077 evalcond[7]=(((new_r01*x1185))+(((-1.0)*gconst13)));
15078 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
15079 {
15080 continue;
15081 }
15082 }
15083 
15084 {
15085 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15086 vinfos[0].jointtype = 1;
15087 vinfos[0].foffset = j0;
15088 vinfos[0].indices[0] = _ij0[0];
15089 vinfos[0].indices[1] = _ij0[1];
15090 vinfos[0].maxsolutions = _nj0;
15091 vinfos[1].jointtype = 1;
15092 vinfos[1].foffset = j1;
15093 vinfos[1].indices[0] = _ij1[0];
15094 vinfos[1].indices[1] = _ij1[1];
15095 vinfos[1].maxsolutions = _nj1;
15096 vinfos[2].jointtype = 1;
15097 vinfos[2].foffset = j2;
15098 vinfos[2].indices[0] = _ij2[0];
15099 vinfos[2].indices[1] = _ij2[1];
15100 vinfos[2].maxsolutions = _nj2;
15101 vinfos[3].jointtype = 1;
15102 vinfos[3].foffset = j3;
15103 vinfos[3].indices[0] = _ij3[0];
15104 vinfos[3].indices[1] = _ij3[1];
15105 vinfos[3].maxsolutions = _nj3;
15106 vinfos[4].jointtype = 1;
15107 vinfos[4].foffset = j4;
15108 vinfos[4].indices[0] = _ij4[0];
15109 vinfos[4].indices[1] = _ij4[1];
15110 vinfos[4].maxsolutions = _nj4;
15111 vinfos[5].jointtype = 1;
15112 vinfos[5].foffset = j5;
15113 vinfos[5].indices[0] = _ij5[0];
15114 vinfos[5].indices[1] = _ij5[1];
15115 vinfos[5].maxsolutions = _nj5;
15116 std::vector<int> vfree(0);
15117 solutions.AddSolution(vinfos,vfree);
15118 }
15119 }
15120 }
15121 
15122 }
15123 
15124 }
15125 
15126 }
15127 } while(0);
15128 if( bgotonextstatement )
15129 {
15130 bool bgotonextstatement = true;
15131 do
15132 {
15133 evalcond[0]=IKabs(new_r10);
15134 if( IKabs(evalcond[0]) < 0.0000050000000000 )
15135 {
15136 bgotonextstatement=false;
15137 {
15138 IkReal j3eval[1];
15139 CheckValue<IkReal> x1189 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15140 if(!x1189.valid){
15141 continue;
15142 }
15143 IkReal x1188=((-1.0)*(x1189.value));
15144 sj4=0;
15145 cj4=-1.0;
15146 j4=3.14159265358979;
15147 sj5=gconst13;
15148 cj5=gconst14;
15149 j5=x1188;
15150 new_r10=0;
15151 IkReal gconst12=x1188;
15152 IkReal x1190 = new_r00*new_r00;
15153 if(IKabs(x1190)==0){
15154 continue;
15155 }
15156 IkReal gconst13=(new_r00*(pow(x1190,-0.5)));
15157 IkReal gconst14=0;
15158 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
15159 if( IKabs(j3eval[0]) < 0.0000010000000000 )
15160 {
15161 {
15162 IkReal j3eval[1];
15163 CheckValue<IkReal> x1192 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15164 if(!x1192.valid){
15165 continue;
15166 }
15167 IkReal x1191=((-1.0)*(x1192.value));
15168 sj4=0;
15169 cj4=-1.0;
15170 j4=3.14159265358979;
15171 sj5=gconst13;
15172 cj5=gconst14;
15173 j5=x1191;
15174 new_r10=0;
15175 IkReal gconst12=x1191;
15176 IkReal x1193 = new_r00*new_r00;
15177 if(IKabs(x1193)==0){
15178 continue;
15179 }
15180 IkReal gconst13=(new_r00*(pow(x1193,-0.5)));
15181 IkReal gconst14=0;
15182 j3eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
15183 if( IKabs(j3eval[0]) < 0.0000010000000000 )
15184 {
15185 {
15186 IkReal j3eval[1];
15187 CheckValue<IkReal> x1195 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15188 if(!x1195.valid){
15189 continue;
15190 }
15191 IkReal x1194=((-1.0)*(x1195.value));
15192 sj4=0;
15193 cj4=-1.0;
15194 j4=3.14159265358979;
15195 sj5=gconst13;
15196 cj5=gconst14;
15197 j5=x1194;
15198 new_r10=0;
15199 IkReal gconst12=x1194;
15200 IkReal x1196 = new_r00*new_r00;
15201 if(IKabs(x1196)==0){
15202 continue;
15203 }
15204 IkReal gconst13=(new_r00*(pow(x1196,-0.5)));
15205 IkReal gconst14=0;
15206 j3eval[0]=new_r00;
15207 if( IKabs(j3eval[0]) < 0.0000010000000000 )
15208 {
15209 continue; // 3 cases reached
15210 
15211 } else
15212 {
15213 {
15214 IkReal j3array[1], cj3array[1], sj3array[1];
15215 bool j3valid[1]={false};
15216 _nj3 = 1;
15217 CheckValue<IkReal> x1197=IKPowWithIntegerCheck(new_r00,-1);
15218 if(!x1197.valid){
15219 continue;
15220 }
15221 CheckValue<IkReal> x1198=IKPowWithIntegerCheck(gconst13,-1);
15222 if(!x1198.valid){
15223 continue;
15224 }
15225 if( IKabs(((-1.0)*gconst13*(x1197.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1198.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst13*(x1197.value)))+IKsqr((new_r01*(x1198.value)))-1) <= IKFAST_SINCOS_THRESH )
15226  continue;
15227 j3array[0]=IKatan2(((-1.0)*gconst13*(x1197.value)), (new_r01*(x1198.value)));
15228 sj3array[0]=IKsin(j3array[0]);
15229 cj3array[0]=IKcos(j3array[0]);
15230 if( j3array[0] > IKPI )
15231 {
15232  j3array[0]-=IK2PI;
15233 }
15234 else if( j3array[0] < -IKPI )
15235 { j3array[0]+=IK2PI;
15236 }
15237 j3valid[0] = true;
15238 for(int ij3 = 0; ij3 < 1; ++ij3)
15239 {
15240 if( !j3valid[ij3] )
15241 {
15242  continue;
15243 }
15244 _ij3[0] = ij3; _ij3[1] = -1;
15245 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15246 {
15247 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15248 {
15249  j3valid[iij3]=false; _ij3[1] = iij3; break;
15250 }
15251 }
15252 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15253 {
15254 IkReal evalcond[8];
15255 IkReal x1199=IKcos(j3);
15256 IkReal x1200=IKsin(j3);
15257 IkReal x1201=(gconst13*x1199);
15258 IkReal x1202=(gconst13*x1200);
15259 evalcond[0]=(new_r00*x1199);
15260 evalcond[1]=((-1.0)*x1201);
15261 evalcond[2]=(((new_r00*x1200))+gconst13);
15262 evalcond[3]=(x1202+new_r00);
15263 evalcond[4]=((((-1.0)*x1201))+new_r01);
15264 evalcond[5]=((((-1.0)*x1202))+new_r11);
15265 evalcond[6]=(((new_r01*x1200))+(((-1.0)*new_r11*x1199)));
15266 evalcond[7]=(((new_r11*x1200))+(((-1.0)*gconst13))+((new_r01*x1199)));
15267 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
15268 {
15269 continue;
15270 }
15271 }
15272 
15273 {
15274 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15275 vinfos[0].jointtype = 1;
15276 vinfos[0].foffset = j0;
15277 vinfos[0].indices[0] = _ij0[0];
15278 vinfos[0].indices[1] = _ij0[1];
15279 vinfos[0].maxsolutions = _nj0;
15280 vinfos[1].jointtype = 1;
15281 vinfos[1].foffset = j1;
15282 vinfos[1].indices[0] = _ij1[0];
15283 vinfos[1].indices[1] = _ij1[1];
15284 vinfos[1].maxsolutions = _nj1;
15285 vinfos[2].jointtype = 1;
15286 vinfos[2].foffset = j2;
15287 vinfos[2].indices[0] = _ij2[0];
15288 vinfos[2].indices[1] = _ij2[1];
15289 vinfos[2].maxsolutions = _nj2;
15290 vinfos[3].jointtype = 1;
15291 vinfos[3].foffset = j3;
15292 vinfos[3].indices[0] = _ij3[0];
15293 vinfos[3].indices[1] = _ij3[1];
15294 vinfos[3].maxsolutions = _nj3;
15295 vinfos[4].jointtype = 1;
15296 vinfos[4].foffset = j4;
15297 vinfos[4].indices[0] = _ij4[0];
15298 vinfos[4].indices[1] = _ij4[1];
15299 vinfos[4].maxsolutions = _nj4;
15300 vinfos[5].jointtype = 1;
15301 vinfos[5].foffset = j5;
15302 vinfos[5].indices[0] = _ij5[0];
15303 vinfos[5].indices[1] = _ij5[1];
15304 vinfos[5].maxsolutions = _nj5;
15305 std::vector<int> vfree(0);
15306 solutions.AddSolution(vinfos,vfree);
15307 }
15308 }
15309 }
15310 
15311 }
15312 
15313 }
15314 
15315 } else
15316 {
15317 {
15318 IkReal j3array[1], cj3array[1], sj3array[1];
15319 bool j3valid[1]={false};
15320 _nj3 = 1;
15321 CheckValue<IkReal> x1203 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
15322 if(!x1203.valid){
15323 continue;
15324 }
15325 CheckValue<IkReal> x1204=IKPowWithIntegerCheck(IKsign(gconst13),-1);
15326 if(!x1204.valid){
15327 continue;
15328 }
15329 j3array[0]=((-1.5707963267949)+(x1203.value)+(((1.5707963267949)*(x1204.value))));
15330 sj3array[0]=IKsin(j3array[0]);
15331 cj3array[0]=IKcos(j3array[0]);
15332 if( j3array[0] > IKPI )
15333 {
15334  j3array[0]-=IK2PI;
15335 }
15336 else if( j3array[0] < -IKPI )
15337 { j3array[0]+=IK2PI;
15338 }
15339 j3valid[0] = true;
15340 for(int ij3 = 0; ij3 < 1; ++ij3)
15341 {
15342 if( !j3valid[ij3] )
15343 {
15344  continue;
15345 }
15346 _ij3[0] = ij3; _ij3[1] = -1;
15347 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15348 {
15349 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15350 {
15351  j3valid[iij3]=false; _ij3[1] = iij3; break;
15352 }
15353 }
15354 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15355 {
15356 IkReal evalcond[8];
15357 IkReal x1205=IKcos(j3);
15358 IkReal x1206=IKsin(j3);
15359 IkReal x1207=(gconst13*x1205);
15360 IkReal x1208=(gconst13*x1206);
15361 evalcond[0]=(new_r00*x1205);
15362 evalcond[1]=((-1.0)*x1207);
15363 evalcond[2]=(((new_r00*x1206))+gconst13);
15364 evalcond[3]=(x1208+new_r00);
15365 evalcond[4]=((((-1.0)*x1207))+new_r01);
15366 evalcond[5]=((((-1.0)*x1208))+new_r11);
15367 evalcond[6]=(((new_r01*x1206))+(((-1.0)*new_r11*x1205)));
15368 evalcond[7]=(((new_r11*x1206))+((new_r01*x1205))+(((-1.0)*gconst13)));
15369 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
15370 {
15371 continue;
15372 }
15373 }
15374 
15375 {
15376 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15377 vinfos[0].jointtype = 1;
15378 vinfos[0].foffset = j0;
15379 vinfos[0].indices[0] = _ij0[0];
15380 vinfos[0].indices[1] = _ij0[1];
15381 vinfos[0].maxsolutions = _nj0;
15382 vinfos[1].jointtype = 1;
15383 vinfos[1].foffset = j1;
15384 vinfos[1].indices[0] = _ij1[0];
15385 vinfos[1].indices[1] = _ij1[1];
15386 vinfos[1].maxsolutions = _nj1;
15387 vinfos[2].jointtype = 1;
15388 vinfos[2].foffset = j2;
15389 vinfos[2].indices[0] = _ij2[0];
15390 vinfos[2].indices[1] = _ij2[1];
15391 vinfos[2].maxsolutions = _nj2;
15392 vinfos[3].jointtype = 1;
15393 vinfos[3].foffset = j3;
15394 vinfos[3].indices[0] = _ij3[0];
15395 vinfos[3].indices[1] = _ij3[1];
15396 vinfos[3].maxsolutions = _nj3;
15397 vinfos[4].jointtype = 1;
15398 vinfos[4].foffset = j4;
15399 vinfos[4].indices[0] = _ij4[0];
15400 vinfos[4].indices[1] = _ij4[1];
15401 vinfos[4].maxsolutions = _nj4;
15402 vinfos[5].jointtype = 1;
15403 vinfos[5].foffset = j5;
15404 vinfos[5].indices[0] = _ij5[0];
15405 vinfos[5].indices[1] = _ij5[1];
15406 vinfos[5].maxsolutions = _nj5;
15407 std::vector<int> vfree(0);
15408 solutions.AddSolution(vinfos,vfree);
15409 }
15410 }
15411 }
15412 
15413 }
15414 
15415 }
15416 
15417 } else
15418 {
15419 {
15420 IkReal j3array[1], cj3array[1], sj3array[1];
15421 bool j3valid[1]={false};
15422 _nj3 = 1;
15423 CheckValue<IkReal> x1209 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
15424 if(!x1209.valid){
15425 continue;
15426 }
15427 CheckValue<IkReal> x1210=IKPowWithIntegerCheck(IKsign(gconst13),-1);
15428 if(!x1210.valid){
15429 continue;
15430 }
15431 j3array[0]=((-1.5707963267949)+(x1209.value)+(((1.5707963267949)*(x1210.value))));
15432 sj3array[0]=IKsin(j3array[0]);
15433 cj3array[0]=IKcos(j3array[0]);
15434 if( j3array[0] > IKPI )
15435 {
15436  j3array[0]-=IK2PI;
15437 }
15438 else if( j3array[0] < -IKPI )
15439 { j3array[0]+=IK2PI;
15440 }
15441 j3valid[0] = true;
15442 for(int ij3 = 0; ij3 < 1; ++ij3)
15443 {
15444 if( !j3valid[ij3] )
15445 {
15446  continue;
15447 }
15448 _ij3[0] = ij3; _ij3[1] = -1;
15449 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15450 {
15451 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15452 {
15453  j3valid[iij3]=false; _ij3[1] = iij3; break;
15454 }
15455 }
15456 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15457 {
15458 IkReal evalcond[8];
15459 IkReal x1211=IKcos(j3);
15460 IkReal x1212=IKsin(j3);
15461 IkReal x1213=(gconst13*x1211);
15462 IkReal x1214=(gconst13*x1212);
15463 evalcond[0]=(new_r00*x1211);
15464 evalcond[1]=((-1.0)*x1213);
15465 evalcond[2]=(gconst13+((new_r00*x1212)));
15466 evalcond[3]=(x1214+new_r00);
15467 evalcond[4]=(new_r01+(((-1.0)*x1213)));
15468 evalcond[5]=(new_r11+(((-1.0)*x1214)));
15469 evalcond[6]=(((new_r01*x1212))+(((-1.0)*new_r11*x1211)));
15470 evalcond[7]=(((new_r11*x1212))+((new_r01*x1211))+(((-1.0)*gconst13)));
15471 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
15472 {
15473 continue;
15474 }
15475 }
15476 
15477 {
15478 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15479 vinfos[0].jointtype = 1;
15480 vinfos[0].foffset = j0;
15481 vinfos[0].indices[0] = _ij0[0];
15482 vinfos[0].indices[1] = _ij0[1];
15483 vinfos[0].maxsolutions = _nj0;
15484 vinfos[1].jointtype = 1;
15485 vinfos[1].foffset = j1;
15486 vinfos[1].indices[0] = _ij1[0];
15487 vinfos[1].indices[1] = _ij1[1];
15488 vinfos[1].maxsolutions = _nj1;
15489 vinfos[2].jointtype = 1;
15490 vinfos[2].foffset = j2;
15491 vinfos[2].indices[0] = _ij2[0];
15492 vinfos[2].indices[1] = _ij2[1];
15493 vinfos[2].maxsolutions = _nj2;
15494 vinfos[3].jointtype = 1;
15495 vinfos[3].foffset = j3;
15496 vinfos[3].indices[0] = _ij3[0];
15497 vinfos[3].indices[1] = _ij3[1];
15498 vinfos[3].maxsolutions = _nj3;
15499 vinfos[4].jointtype = 1;
15500 vinfos[4].foffset = j4;
15501 vinfos[4].indices[0] = _ij4[0];
15502 vinfos[4].indices[1] = _ij4[1];
15503 vinfos[4].maxsolutions = _nj4;
15504 vinfos[5].jointtype = 1;
15505 vinfos[5].foffset = j5;
15506 vinfos[5].indices[0] = _ij5[0];
15507 vinfos[5].indices[1] = _ij5[1];
15508 vinfos[5].maxsolutions = _nj5;
15509 std::vector<int> vfree(0);
15510 solutions.AddSolution(vinfos,vfree);
15511 }
15512 }
15513 }
15514 
15515 }
15516 
15517 }
15518 
15519 }
15520 } while(0);
15521 if( bgotonextstatement )
15522 {
15523 bool bgotonextstatement = true;
15524 do
15525 {
15526 if( 1 )
15527 {
15528 bgotonextstatement=false;
15529 continue; // branch miss [j3]
15530 
15531 }
15532 } while(0);
15533 if( bgotonextstatement )
15534 {
15535 }
15536 }
15537 }
15538 }
15539 }
15540 }
15541 }
15542 
15543 } else
15544 {
15545 {
15546 IkReal j3array[1], cj3array[1], sj3array[1];
15547 bool j3valid[1]={false};
15548 _nj3 = 1;
15549 IkReal x1215=((1.0)*gconst14);
15550 CheckValue<IkReal> x1216=IKPowWithIntegerCheck(IKsign((((gconst13*new_r00))+(((-1.0)*new_r10*x1215)))),-1);
15551 if(!x1216.valid){
15552 continue;
15553 }
15554 CheckValue<IkReal> x1217 = IKatan2WithCheck(IkReal(((gconst14*gconst14)+(((-1.0)*(new_r00*new_r00))))),IkReal((((new_r00*new_r10))+(((-1.0)*gconst13*x1215)))),IKFAST_ATAN2_MAGTHRESH);
15555 if(!x1217.valid){
15556 continue;
15557 }
15558 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1216.value)))+(x1217.value));
15559 sj3array[0]=IKsin(j3array[0]);
15560 cj3array[0]=IKcos(j3array[0]);
15561 if( j3array[0] > IKPI )
15562 {
15563  j3array[0]-=IK2PI;
15564 }
15565 else if( j3array[0] < -IKPI )
15566 { j3array[0]+=IK2PI;
15567 }
15568 j3valid[0] = true;
15569 for(int ij3 = 0; ij3 < 1; ++ij3)
15570 {
15571 if( !j3valid[ij3] )
15572 {
15573  continue;
15574 }
15575 _ij3[0] = ij3; _ij3[1] = -1;
15576 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15577 {
15578 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15579 {
15580  j3valid[iij3]=false; _ij3[1] = iij3; break;
15581 }
15582 }
15583 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15584 {
15585 IkReal evalcond[8];
15586 IkReal x1218=IKsin(j3);
15587 IkReal x1219=IKcos(j3);
15588 IkReal x1220=(gconst14*x1218);
15589 IkReal x1221=((1.0)*x1219);
15590 IkReal x1222=(gconst13*x1218);
15591 IkReal x1223=(gconst13*x1221);
15592 evalcond[0]=(((new_r10*x1218))+gconst14+((new_r00*x1219)));
15593 evalcond[1]=(x1222+((gconst14*x1219))+new_r00);
15594 evalcond[2]=(gconst13+((new_r00*x1218))+(((-1.0)*new_r10*x1221)));
15595 evalcond[3]=(gconst14+((new_r01*x1218))+(((-1.0)*new_r11*x1221)));
15596 evalcond[4]=(x1220+(((-1.0)*x1223))+new_r01);
15597 evalcond[5]=(x1220+(((-1.0)*x1223))+new_r10);
15598 evalcond[6]=(((new_r11*x1218))+((new_r01*x1219))+(((-1.0)*gconst13)));
15599 evalcond[7]=((((-1.0)*x1222))+new_r11+(((-1.0)*gconst14*x1221)));
15600 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
15601 {
15602 continue;
15603 }
15604 }
15605 
15606 {
15607 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15608 vinfos[0].jointtype = 1;
15609 vinfos[0].foffset = j0;
15610 vinfos[0].indices[0] = _ij0[0];
15611 vinfos[0].indices[1] = _ij0[1];
15612 vinfos[0].maxsolutions = _nj0;
15613 vinfos[1].jointtype = 1;
15614 vinfos[1].foffset = j1;
15615 vinfos[1].indices[0] = _ij1[0];
15616 vinfos[1].indices[1] = _ij1[1];
15617 vinfos[1].maxsolutions = _nj1;
15618 vinfos[2].jointtype = 1;
15619 vinfos[2].foffset = j2;
15620 vinfos[2].indices[0] = _ij2[0];
15621 vinfos[2].indices[1] = _ij2[1];
15622 vinfos[2].maxsolutions = _nj2;
15623 vinfos[3].jointtype = 1;
15624 vinfos[3].foffset = j3;
15625 vinfos[3].indices[0] = _ij3[0];
15626 vinfos[3].indices[1] = _ij3[1];
15627 vinfos[3].maxsolutions = _nj3;
15628 vinfos[4].jointtype = 1;
15629 vinfos[4].foffset = j4;
15630 vinfos[4].indices[0] = _ij4[0];
15631 vinfos[4].indices[1] = _ij4[1];
15632 vinfos[4].maxsolutions = _nj4;
15633 vinfos[5].jointtype = 1;
15634 vinfos[5].foffset = j5;
15635 vinfos[5].indices[0] = _ij5[0];
15636 vinfos[5].indices[1] = _ij5[1];
15637 vinfos[5].maxsolutions = _nj5;
15638 std::vector<int> vfree(0);
15639 solutions.AddSolution(vinfos,vfree);
15640 }
15641 }
15642 }
15643 
15644 }
15645 
15646 }
15647 
15648 } else
15649 {
15650 {
15651 IkReal j3array[1], cj3array[1], sj3array[1];
15652 bool j3valid[1]={false};
15653 _nj3 = 1;
15654 IkReal x1224=((1.0)*gconst14);
15655 CheckValue<IkReal> x1225 = IKatan2WithCheck(IkReal(((gconst14*gconst14)+((new_r00*new_r11)))),IkReal((((new_r00*new_r01))+(((-1.0)*gconst13*x1224)))),IKFAST_ATAN2_MAGTHRESH);
15656 if(!x1225.valid){
15657 continue;
15658 }
15659 CheckValue<IkReal> x1226=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst13*new_r11))+(((-1.0)*new_r01*x1224)))),-1);
15660 if(!x1226.valid){
15661 continue;
15662 }
15663 j3array[0]=((-1.5707963267949)+(x1225.value)+(((1.5707963267949)*(x1226.value))));
15664 sj3array[0]=IKsin(j3array[0]);
15665 cj3array[0]=IKcos(j3array[0]);
15666 if( j3array[0] > IKPI )
15667 {
15668  j3array[0]-=IK2PI;
15669 }
15670 else if( j3array[0] < -IKPI )
15671 { j3array[0]+=IK2PI;
15672 }
15673 j3valid[0] = true;
15674 for(int ij3 = 0; ij3 < 1; ++ij3)
15675 {
15676 if( !j3valid[ij3] )
15677 {
15678  continue;
15679 }
15680 _ij3[0] = ij3; _ij3[1] = -1;
15681 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15682 {
15683 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15684 {
15685  j3valid[iij3]=false; _ij3[1] = iij3; break;
15686 }
15687 }
15688 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15689 {
15690 IkReal evalcond[8];
15691 IkReal x1227=IKsin(j3);
15692 IkReal x1228=IKcos(j3);
15693 IkReal x1229=(gconst14*x1227);
15694 IkReal x1230=((1.0)*x1228);
15695 IkReal x1231=(gconst13*x1227);
15696 IkReal x1232=(gconst13*x1230);
15697 evalcond[0]=(gconst14+((new_r00*x1228))+((new_r10*x1227)));
15698 evalcond[1]=(x1231+new_r00+((gconst14*x1228)));
15699 evalcond[2]=(gconst13+((new_r00*x1227))+(((-1.0)*new_r10*x1230)));
15700 evalcond[3]=(gconst14+((new_r01*x1227))+(((-1.0)*new_r11*x1230)));
15701 evalcond[4]=(x1229+(((-1.0)*x1232))+new_r01);
15702 evalcond[5]=(x1229+(((-1.0)*x1232))+new_r10);
15703 evalcond[6]=(((new_r11*x1227))+((new_r01*x1228))+(((-1.0)*gconst13)));
15704 evalcond[7]=((((-1.0)*x1231))+new_r11+(((-1.0)*gconst14*x1230)));
15705 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
15706 {
15707 continue;
15708 }
15709 }
15710 
15711 {
15712 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15713 vinfos[0].jointtype = 1;
15714 vinfos[0].foffset = j0;
15715 vinfos[0].indices[0] = _ij0[0];
15716 vinfos[0].indices[1] = _ij0[1];
15717 vinfos[0].maxsolutions = _nj0;
15718 vinfos[1].jointtype = 1;
15719 vinfos[1].foffset = j1;
15720 vinfos[1].indices[0] = _ij1[0];
15721 vinfos[1].indices[1] = _ij1[1];
15722 vinfos[1].maxsolutions = _nj1;
15723 vinfos[2].jointtype = 1;
15724 vinfos[2].foffset = j2;
15725 vinfos[2].indices[0] = _ij2[0];
15726 vinfos[2].indices[1] = _ij2[1];
15727 vinfos[2].maxsolutions = _nj2;
15728 vinfos[3].jointtype = 1;
15729 vinfos[3].foffset = j3;
15730 vinfos[3].indices[0] = _ij3[0];
15731 vinfos[3].indices[1] = _ij3[1];
15732 vinfos[3].maxsolutions = _nj3;
15733 vinfos[4].jointtype = 1;
15734 vinfos[4].foffset = j4;
15735 vinfos[4].indices[0] = _ij4[0];
15736 vinfos[4].indices[1] = _ij4[1];
15737 vinfos[4].maxsolutions = _nj4;
15738 vinfos[5].jointtype = 1;
15739 vinfos[5].foffset = j5;
15740 vinfos[5].indices[0] = _ij5[0];
15741 vinfos[5].indices[1] = _ij5[1];
15742 vinfos[5].maxsolutions = _nj5;
15743 std::vector<int> vfree(0);
15744 solutions.AddSolution(vinfos,vfree);
15745 }
15746 }
15747 }
15748 
15749 }
15750 
15751 }
15752 
15753 } else
15754 {
15755 {
15756 IkReal j3array[1], cj3array[1], sj3array[1];
15757 bool j3valid[1]={false};
15758 _nj3 = 1;
15759 IkReal x1233=((1.0)*new_r10);
15760 CheckValue<IkReal> x1234=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*new_r01))+(((-1.0)*new_r11*x1233)))),-1);
15761 if(!x1234.valid){
15762 continue;
15763 }
15764 CheckValue<IkReal> x1235 = IKatan2WithCheck(IkReal((((gconst14*new_r00))+((gconst14*new_r11)))),IkReal((((gconst14*new_r01))+(((-1.0)*gconst14*x1233)))),IKFAST_ATAN2_MAGTHRESH);
15765 if(!x1235.valid){
15766 continue;
15767 }
15768 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1234.value)))+(x1235.value));
15769 sj3array[0]=IKsin(j3array[0]);
15770 cj3array[0]=IKcos(j3array[0]);
15771 if( j3array[0] > IKPI )
15772 {
15773  j3array[0]-=IK2PI;
15774 }
15775 else if( j3array[0] < -IKPI )
15776 { j3array[0]+=IK2PI;
15777 }
15778 j3valid[0] = true;
15779 for(int ij3 = 0; ij3 < 1; ++ij3)
15780 {
15781 if( !j3valid[ij3] )
15782 {
15783  continue;
15784 }
15785 _ij3[0] = ij3; _ij3[1] = -1;
15786 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15787 {
15788 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15789 {
15790  j3valid[iij3]=false; _ij3[1] = iij3; break;
15791 }
15792 }
15793 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15794 {
15795 IkReal evalcond[8];
15796 IkReal x1236=IKsin(j3);
15797 IkReal x1237=IKcos(j3);
15798 IkReal x1238=(gconst14*x1236);
15799 IkReal x1239=((1.0)*x1237);
15800 IkReal x1240=(gconst13*x1236);
15801 IkReal x1241=(gconst13*x1239);
15802 evalcond[0]=(gconst14+((new_r10*x1236))+((new_r00*x1237)));
15803 evalcond[1]=(((gconst14*x1237))+x1240+new_r00);
15804 evalcond[2]=(gconst13+((new_r00*x1236))+(((-1.0)*new_r10*x1239)));
15805 evalcond[3]=(gconst14+((new_r01*x1236))+(((-1.0)*new_r11*x1239)));
15806 evalcond[4]=(x1238+(((-1.0)*x1241))+new_r01);
15807 evalcond[5]=(x1238+(((-1.0)*x1241))+new_r10);
15808 evalcond[6]=(((new_r01*x1237))+((new_r11*x1236))+(((-1.0)*gconst13)));
15809 evalcond[7]=((((-1.0)*x1240))+new_r11+(((-1.0)*gconst14*x1239)));
15810 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
15811 {
15812 continue;
15813 }
15814 }
15815 
15816 {
15817 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15818 vinfos[0].jointtype = 1;
15819 vinfos[0].foffset = j0;
15820 vinfos[0].indices[0] = _ij0[0];
15821 vinfos[0].indices[1] = _ij0[1];
15822 vinfos[0].maxsolutions = _nj0;
15823 vinfos[1].jointtype = 1;
15824 vinfos[1].foffset = j1;
15825 vinfos[1].indices[0] = _ij1[0];
15826 vinfos[1].indices[1] = _ij1[1];
15827 vinfos[1].maxsolutions = _nj1;
15828 vinfos[2].jointtype = 1;
15829 vinfos[2].foffset = j2;
15830 vinfos[2].indices[0] = _ij2[0];
15831 vinfos[2].indices[1] = _ij2[1];
15832 vinfos[2].maxsolutions = _nj2;
15833 vinfos[3].jointtype = 1;
15834 vinfos[3].foffset = j3;
15835 vinfos[3].indices[0] = _ij3[0];
15836 vinfos[3].indices[1] = _ij3[1];
15837 vinfos[3].maxsolutions = _nj3;
15838 vinfos[4].jointtype = 1;
15839 vinfos[4].foffset = j4;
15840 vinfos[4].indices[0] = _ij4[0];
15841 vinfos[4].indices[1] = _ij4[1];
15842 vinfos[4].maxsolutions = _nj4;
15843 vinfos[5].jointtype = 1;
15844 vinfos[5].foffset = j5;
15845 vinfos[5].indices[0] = _ij5[0];
15846 vinfos[5].indices[1] = _ij5[1];
15847 vinfos[5].maxsolutions = _nj5;
15848 std::vector<int> vfree(0);
15849 solutions.AddSolution(vinfos,vfree);
15850 }
15851 }
15852 }
15853 
15854 }
15855 
15856 }
15857 
15858 }
15859 } while(0);
15860 if( bgotonextstatement )
15861 {
15862 bool bgotonextstatement = true;
15863 do
15864 {
15865 IkReal x1242=((-1.0)*new_r00);
15866 IkReal x1244 = ((new_r10*new_r10)+(new_r00*new_r00));
15867 if(IKabs(x1244)==0){
15868 continue;
15869 }
15870 IkReal x1243=pow(x1244,-0.5);
15871 CheckValue<IkReal> x1245 = IKatan2WithCheck(IkReal(x1242),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
15872 if(!x1245.valid){
15873 continue;
15874 }
15875 IkReal gconst15=((3.14159265358979)+(((-1.0)*(x1245.value))));
15876 IkReal gconst16=(x1242*x1243);
15877 IkReal gconst17=((1.0)*new_r10*x1243);
15878 CheckValue<IkReal> x1246 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
15879 if(!x1246.valid){
15880 continue;
15881 }
15882 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x1246.value)+j5)))), 6.28318530717959)));
15883 if( IKabs(evalcond[0]) < 0.0000050000000000 )
15884 {
15885 bgotonextstatement=false;
15886 {
15887 IkReal j3eval[3];
15888 IkReal x1247=((-1.0)*new_r00);
15889 CheckValue<IkReal> x1250 = IKatan2WithCheck(IkReal(x1247),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
15890 if(!x1250.valid){
15891 continue;
15892 }
15893 IkReal x1248=((1.0)*(x1250.value));
15894 IkReal x1249=x1243;
15895 sj4=0;
15896 cj4=-1.0;
15897 j4=3.14159265358979;
15898 sj5=gconst16;
15899 cj5=gconst17;
15900 j5=((3.14159265)+(((-1.0)*x1248)));
15901 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1248)));
15902 IkReal gconst16=(x1247*x1249);
15903 IkReal gconst17=((1.0)*new_r10*x1249);
15904 IkReal x1251=new_r10*new_r10;
15905 IkReal x1252=(new_r10*new_r11);
15906 IkReal x1253=((((-1.0)*new_r00*new_r01))+(((-1.0)*x1252)));
15907 IkReal x1254=x1243;
15908 IkReal x1255=(new_r10*x1254);
15909 j3eval[0]=x1253;
15910 j3eval[1]=((IKabs((((new_r01*x1255))+(((-1.0)*x1251*x1254)))))+(IKabs((((new_r00*x1255))+((x1252*x1254))))));
15911 j3eval[2]=IKsign(x1253);
15912 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
15913 {
15914 {
15915 IkReal j3eval[1];
15916 IkReal x1256=((-1.0)*new_r00);
15917 CheckValue<IkReal> x1259 = IKatan2WithCheck(IkReal(x1256),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
15918 if(!x1259.valid){
15919 continue;
15920 }
15921 IkReal x1257=((1.0)*(x1259.value));
15922 IkReal x1258=x1243;
15923 sj4=0;
15924 cj4=-1.0;
15925 j4=3.14159265358979;
15926 sj5=gconst16;
15927 cj5=gconst17;
15928 j5=((3.14159265)+(((-1.0)*x1257)));
15929 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1257)));
15930 IkReal gconst16=(x1256*x1258);
15931 IkReal gconst17=((1.0)*new_r10*x1258);
15932 IkReal x1260=new_r10*new_r10;
15933 IkReal x1261=new_r00*new_r00*new_r00;
15934 CheckValue<IkReal> x1265=IKPowWithIntegerCheck((x1260+(new_r00*new_r00)),-1);
15935 if(!x1265.valid){
15936 continue;
15937 }
15938 IkReal x1262=x1265.value;
15939 IkReal x1263=(x1260*x1262);
15940 IkReal x1264=(x1261*x1262);
15941 j3eval[0]=((IKabs((((new_r00*new_r10*x1262))+((new_r01*x1264))+((new_r00*new_r01*x1263)))))+(IKabs((x1263+((new_r11*x1264))+((new_r00*new_r11*x1263))))));
15942 if( IKabs(j3eval[0]) < 0.0000010000000000 )
15943 {
15944 {
15945 IkReal j3eval[1];
15946 IkReal x1266=((-1.0)*new_r00);
15947 CheckValue<IkReal> x1269 = IKatan2WithCheck(IkReal(x1266),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
15948 if(!x1269.valid){
15949 continue;
15950 }
15951 IkReal x1267=((1.0)*(x1269.value));
15952 IkReal x1268=x1243;
15953 sj4=0;
15954 cj4=-1.0;
15955 j4=3.14159265358979;
15956 sj5=gconst16;
15957 cj5=gconst17;
15958 j5=((3.14159265)+(((-1.0)*x1267)));
15959 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1267)));
15960 IkReal gconst16=(x1266*x1268);
15961 IkReal gconst17=((1.0)*new_r10*x1268);
15962 IkReal x1270=new_r10*new_r10;
15963 IkReal x1271=new_r00*new_r00;
15964 CheckValue<IkReal> x1275=IKPowWithIntegerCheck((x1270+x1271),-1);
15965 if(!x1275.valid){
15966 continue;
15967 }
15968 IkReal x1272=x1275.value;
15969 IkReal x1273=(new_r10*x1272);
15970 IkReal x1274=(x1270*x1272);
15971 j3eval[0]=((IKabs(((((-1.0)*x1271*x1274))+x1274+(((-1.0)*x1272*(x1271*x1271))))))+(IKabs((((new_r00*x1273))+((x1273*(new_r00*new_r00*new_r00)))+((new_r00*x1273*(new_r10*new_r10)))))));
15972 if( IKabs(j3eval[0]) < 0.0000010000000000 )
15973 {
15974 {
15975 IkReal evalcond[2];
15976 bool bgotonextstatement = true;
15977 do
15978 {
15979 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
15980 if( IKabs(evalcond[0]) < 0.0000050000000000 )
15981 {
15982 bgotonextstatement=false;
15983 {
15984 IkReal j3eval[1];
15985 CheckValue<IkReal> x1277 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
15986 if(!x1277.valid){
15987 continue;
15988 }
15989 IkReal x1276=((1.0)*(x1277.value));
15990 sj4=0;
15991 cj4=-1.0;
15992 j4=3.14159265358979;
15993 sj5=gconst16;
15994 cj5=gconst17;
15995 j5=((3.14159265)+(((-1.0)*x1276)));
15996 new_r11=0;
15997 new_r00=0;
15998 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1276)));
15999 IkReal gconst16=0;
16000 IkReal x1278 = new_r10*new_r10;
16001 if(IKabs(x1278)==0){
16002 continue;
16003 }
16004 IkReal gconst17=((1.0)*new_r10*(pow(x1278,-0.5)));
16005 j3eval[0]=new_r01;
16006 if( IKabs(j3eval[0]) < 0.0000010000000000 )
16007 {
16008 {
16009 IkReal j3array[2], cj3array[2], sj3array[2];
16010 bool j3valid[2]={false};
16011 _nj3 = 2;
16012 CheckValue<IkReal> x1279=IKPowWithIntegerCheck(gconst17,-1);
16013 if(!x1279.valid){
16014 continue;
16015 }
16016 sj3array[0]=((-1.0)*new_r01*(x1279.value));
16017 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
16018 {
16019  j3valid[0] = j3valid[1] = true;
16020  j3array[0] = IKasin(sj3array[0]);
16021  cj3array[0] = IKcos(j3array[0]);
16022  sj3array[1] = sj3array[0];
16023  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
16024  cj3array[1] = -cj3array[0];
16025 }
16026 else if( isnan(sj3array[0]) )
16027 {
16028  // probably any value will work
16029  j3valid[0] = true;
16030  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
16031 }
16032 for(int ij3 = 0; ij3 < 2; ++ij3)
16033 {
16034 if( !j3valid[ij3] )
16035 {
16036  continue;
16037 }
16038 _ij3[0] = ij3; _ij3[1] = -1;
16039 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
16040 {
16041 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16042 {
16043  j3valid[iij3]=false; _ij3[1] = iij3; break;
16044 }
16045 }
16046 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16047 {
16048 IkReal evalcond[6];
16049 IkReal x1280=IKcos(j3);
16050 IkReal x1281=IKsin(j3);
16051 evalcond[0]=(new_r01*x1280);
16052 evalcond[1]=(gconst17*x1280);
16053 evalcond[2]=((-1.0)*new_r10*x1280);
16054 evalcond[3]=(gconst17+((new_r01*x1281)));
16055 evalcond[4]=(((new_r10*x1281))+gconst17);
16056 evalcond[5]=(new_r10+((gconst17*x1281)));
16057 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16058 {
16059 continue;
16060 }
16061 }
16062 
16063 {
16064 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16065 vinfos[0].jointtype = 1;
16066 vinfos[0].foffset = j0;
16067 vinfos[0].indices[0] = _ij0[0];
16068 vinfos[0].indices[1] = _ij0[1];
16069 vinfos[0].maxsolutions = _nj0;
16070 vinfos[1].jointtype = 1;
16071 vinfos[1].foffset = j1;
16072 vinfos[1].indices[0] = _ij1[0];
16073 vinfos[1].indices[1] = _ij1[1];
16074 vinfos[1].maxsolutions = _nj1;
16075 vinfos[2].jointtype = 1;
16076 vinfos[2].foffset = j2;
16077 vinfos[2].indices[0] = _ij2[0];
16078 vinfos[2].indices[1] = _ij2[1];
16079 vinfos[2].maxsolutions = _nj2;
16080 vinfos[3].jointtype = 1;
16081 vinfos[3].foffset = j3;
16082 vinfos[3].indices[0] = _ij3[0];
16083 vinfos[3].indices[1] = _ij3[1];
16084 vinfos[3].maxsolutions = _nj3;
16085 vinfos[4].jointtype = 1;
16086 vinfos[4].foffset = j4;
16087 vinfos[4].indices[0] = _ij4[0];
16088 vinfos[4].indices[1] = _ij4[1];
16089 vinfos[4].maxsolutions = _nj4;
16090 vinfos[5].jointtype = 1;
16091 vinfos[5].foffset = j5;
16092 vinfos[5].indices[0] = _ij5[0];
16093 vinfos[5].indices[1] = _ij5[1];
16094 vinfos[5].maxsolutions = _nj5;
16095 std::vector<int> vfree(0);
16096 solutions.AddSolution(vinfos,vfree);
16097 }
16098 }
16099 }
16100 
16101 } else
16102 {
16103 {
16104 IkReal j3array[2], cj3array[2], sj3array[2];
16105 bool j3valid[2]={false};
16106 _nj3 = 2;
16107 CheckValue<IkReal> x1282=IKPowWithIntegerCheck(new_r01,-1);
16108 if(!x1282.valid){
16109 continue;
16110 }
16111 sj3array[0]=((-1.0)*gconst17*(x1282.value));
16112 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
16113 {
16114  j3valid[0] = j3valid[1] = true;
16115  j3array[0] = IKasin(sj3array[0]);
16116  cj3array[0] = IKcos(j3array[0]);
16117  sj3array[1] = sj3array[0];
16118  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
16119  cj3array[1] = -cj3array[0];
16120 }
16121 else if( isnan(sj3array[0]) )
16122 {
16123  // probably any value will work
16124  j3valid[0] = true;
16125  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
16126 }
16127 for(int ij3 = 0; ij3 < 2; ++ij3)
16128 {
16129 if( !j3valid[ij3] )
16130 {
16131  continue;
16132 }
16133 _ij3[0] = ij3; _ij3[1] = -1;
16134 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
16135 {
16136 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16137 {
16138  j3valid[iij3]=false; _ij3[1] = iij3; break;
16139 }
16140 }
16141 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16142 {
16143 IkReal evalcond[6];
16144 IkReal x1283=IKcos(j3);
16145 IkReal x1284=IKsin(j3);
16146 IkReal x1285=(gconst17*x1284);
16147 evalcond[0]=(new_r01*x1283);
16148 evalcond[1]=(gconst17*x1283);
16149 evalcond[2]=((-1.0)*new_r10*x1283);
16150 evalcond[3]=(x1285+new_r01);
16151 evalcond[4]=(((new_r10*x1284))+gconst17);
16152 evalcond[5]=(x1285+new_r10);
16153 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16154 {
16155 continue;
16156 }
16157 }
16158 
16159 {
16160 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16161 vinfos[0].jointtype = 1;
16162 vinfos[0].foffset = j0;
16163 vinfos[0].indices[0] = _ij0[0];
16164 vinfos[0].indices[1] = _ij0[1];
16165 vinfos[0].maxsolutions = _nj0;
16166 vinfos[1].jointtype = 1;
16167 vinfos[1].foffset = j1;
16168 vinfos[1].indices[0] = _ij1[0];
16169 vinfos[1].indices[1] = _ij1[1];
16170 vinfos[1].maxsolutions = _nj1;
16171 vinfos[2].jointtype = 1;
16172 vinfos[2].foffset = j2;
16173 vinfos[2].indices[0] = _ij2[0];
16174 vinfos[2].indices[1] = _ij2[1];
16175 vinfos[2].maxsolutions = _nj2;
16176 vinfos[3].jointtype = 1;
16177 vinfos[3].foffset = j3;
16178 vinfos[3].indices[0] = _ij3[0];
16179 vinfos[3].indices[1] = _ij3[1];
16180 vinfos[3].maxsolutions = _nj3;
16181 vinfos[4].jointtype = 1;
16182 vinfos[4].foffset = j4;
16183 vinfos[4].indices[0] = _ij4[0];
16184 vinfos[4].indices[1] = _ij4[1];
16185 vinfos[4].maxsolutions = _nj4;
16186 vinfos[5].jointtype = 1;
16187 vinfos[5].foffset = j5;
16188 vinfos[5].indices[0] = _ij5[0];
16189 vinfos[5].indices[1] = _ij5[1];
16190 vinfos[5].maxsolutions = _nj5;
16191 std::vector<int> vfree(0);
16192 solutions.AddSolution(vinfos,vfree);
16193 }
16194 }
16195 }
16196 
16197 }
16198 
16199 }
16200 
16201 }
16202 } while(0);
16203 if( bgotonextstatement )
16204 {
16205 bool bgotonextstatement = true;
16206 do
16207 {
16208 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
16209 evalcond[1]=gconst17;
16210 if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
16211 {
16212 bgotonextstatement=false;
16213 {
16214 IkReal j3eval[3];
16215 IkReal x1286=((-1.0)*new_r00);
16216 CheckValue<IkReal> x1288 = IKatan2WithCheck(IkReal(x1286),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
16217 if(!x1288.valid){
16218 continue;
16219 }
16220 IkReal x1287=((1.0)*(x1288.value));
16221 sj4=0;
16222 cj4=-1.0;
16223 j4=3.14159265358979;
16224 sj5=gconst16;
16225 cj5=gconst17;
16226 j5=((3.14159265)+(((-1.0)*x1287)));
16227 new_r11=0;
16228 new_r01=0;
16229 new_r22=0;
16230 new_r20=0;
16231 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1287)));
16232 IkReal gconst16=x1286;
16233 IkReal gconst17=((1.0)*new_r10);
16234 j3eval[0]=1.0;
16235 j3eval[1]=1.0;
16236 j3eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10))));
16237 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
16238 {
16239 {
16240 IkReal j3eval[3];
16241 IkReal x1289=((-1.0)*new_r00);
16242 CheckValue<IkReal> x1291 = IKatan2WithCheck(IkReal(x1289),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
16243 if(!x1291.valid){
16244 continue;
16245 }
16246 IkReal x1290=((1.0)*(x1291.value));
16247 sj4=0;
16248 cj4=-1.0;
16249 j4=3.14159265358979;
16250 sj5=gconst16;
16251 cj5=gconst17;
16252 j5=((3.14159265)+(((-1.0)*x1290)));
16253 new_r11=0;
16254 new_r01=0;
16255 new_r22=0;
16256 new_r20=0;
16257 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1290)));
16258 IkReal gconst16=x1289;
16259 IkReal gconst17=((1.0)*new_r10);
16260 j3eval[0]=-1.0;
16261 j3eval[1]=-1.0;
16262 j3eval[2]=((IKabs(((1.0)*new_r00*new_r10)))+(IKabs(((-1.0)+(new_r10*new_r10)))));
16263 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
16264 {
16265 {
16266 IkReal j3eval[3];
16267 IkReal x1292=((-1.0)*new_r00);
16268 CheckValue<IkReal> x1294 = IKatan2WithCheck(IkReal(x1292),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
16269 if(!x1294.valid){
16270 continue;
16271 }
16272 IkReal x1293=((1.0)*(x1294.value));
16273 sj4=0;
16274 cj4=-1.0;
16275 j4=3.14159265358979;
16276 sj5=gconst16;
16277 cj5=gconst17;
16278 j5=((3.14159265)+(((-1.0)*x1293)));
16279 new_r11=0;
16280 new_r01=0;
16281 new_r22=0;
16282 new_r20=0;
16283 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1293)));
16284 IkReal gconst16=x1292;
16285 IkReal gconst17=((1.0)*new_r10);
16286 j3eval[0]=-1.0;
16287 j3eval[1]=-1.0;
16288 j3eval[2]=((IKabs(((-1.0)+(((2.0)*(new_r10*new_r10))))))+(IKabs(((2.0)*new_r00*new_r10))));
16289 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
16290 {
16291 continue; // 3 cases reached
16292 
16293 } else
16294 {
16295 {
16296 IkReal j3array[1], cj3array[1], sj3array[1];
16297 bool j3valid[1]={false};
16298 _nj3 = 1;
16299 IkReal x1295=((1.0)*gconst17);
16300 CheckValue<IkReal> x1296 = IKatan2WithCheck(IkReal(((((-1.0)*(new_r00*new_r00)))+(gconst17*gconst17))),IkReal(((((-1.0)*gconst16*x1295))+((new_r00*new_r10)))),IKFAST_ATAN2_MAGTHRESH);
16301 if(!x1296.valid){
16302 continue;
16303 }
16304 CheckValue<IkReal> x1297=IKPowWithIntegerCheck(IKsign((((gconst16*new_r00))+(((-1.0)*new_r10*x1295)))),-1);
16305 if(!x1297.valid){
16306 continue;
16307 }
16308 j3array[0]=((-1.5707963267949)+(x1296.value)+(((1.5707963267949)*(x1297.value))));
16309 sj3array[0]=IKsin(j3array[0]);
16310 cj3array[0]=IKcos(j3array[0]);
16311 if( j3array[0] > IKPI )
16312 {
16313  j3array[0]-=IK2PI;
16314 }
16315 else if( j3array[0] < -IKPI )
16316 { j3array[0]+=IK2PI;
16317 }
16318 j3valid[0] = true;
16319 for(int ij3 = 0; ij3 < 1; ++ij3)
16320 {
16321 if( !j3valid[ij3] )
16322 {
16323  continue;
16324 }
16325 _ij3[0] = ij3; _ij3[1] = -1;
16326 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16327 {
16328 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16329 {
16330  j3valid[iij3]=false; _ij3[1] = iij3; break;
16331 }
16332 }
16333 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16334 {
16335 IkReal evalcond[6];
16336 IkReal x1298=IKsin(j3);
16337 IkReal x1299=IKcos(j3);
16338 IkReal x1300=(gconst17*x1298);
16339 IkReal x1301=(gconst16*x1298);
16340 IkReal x1302=(gconst17*x1299);
16341 IkReal x1303=((1.0)*x1299);
16342 IkReal x1304=(gconst16*x1303);
16343 evalcond[0]=(x1300+(((-1.0)*x1304)));
16344 evalcond[1]=(gconst17+((new_r10*x1298))+((new_r00*x1299)));
16345 evalcond[2]=(x1301+x1302+new_r00);
16346 evalcond[3]=((((-1.0)*new_r10*x1303))+gconst16+((new_r00*x1298)));
16347 evalcond[4]=((((-1.0)*x1301))+(((-1.0)*x1302)));
16348 evalcond[5]=(x1300+(((-1.0)*x1304))+new_r10);
16349 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16350 {
16351 continue;
16352 }
16353 }
16354 
16355 {
16356 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16357 vinfos[0].jointtype = 1;
16358 vinfos[0].foffset = j0;
16359 vinfos[0].indices[0] = _ij0[0];
16360 vinfos[0].indices[1] = _ij0[1];
16361 vinfos[0].maxsolutions = _nj0;
16362 vinfos[1].jointtype = 1;
16363 vinfos[1].foffset = j1;
16364 vinfos[1].indices[0] = _ij1[0];
16365 vinfos[1].indices[1] = _ij1[1];
16366 vinfos[1].maxsolutions = _nj1;
16367 vinfos[2].jointtype = 1;
16368 vinfos[2].foffset = j2;
16369 vinfos[2].indices[0] = _ij2[0];
16370 vinfos[2].indices[1] = _ij2[1];
16371 vinfos[2].maxsolutions = _nj2;
16372 vinfos[3].jointtype = 1;
16373 vinfos[3].foffset = j3;
16374 vinfos[3].indices[0] = _ij3[0];
16375 vinfos[3].indices[1] = _ij3[1];
16376 vinfos[3].maxsolutions = _nj3;
16377 vinfos[4].jointtype = 1;
16378 vinfos[4].foffset = j4;
16379 vinfos[4].indices[0] = _ij4[0];
16380 vinfos[4].indices[1] = _ij4[1];
16381 vinfos[4].maxsolutions = _nj4;
16382 vinfos[5].jointtype = 1;
16383 vinfos[5].foffset = j5;
16384 vinfos[5].indices[0] = _ij5[0];
16385 vinfos[5].indices[1] = _ij5[1];
16386 vinfos[5].maxsolutions = _nj5;
16387 std::vector<int> vfree(0);
16388 solutions.AddSolution(vinfos,vfree);
16389 }
16390 }
16391 }
16392 
16393 }
16394 
16395 }
16396 
16397 } else
16398 {
16399 {
16400 IkReal j3array[1], cj3array[1], sj3array[1];
16401 bool j3valid[1]={false};
16402 _nj3 = 1;
16403 CheckValue<IkReal> x1305=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst17*gconst17)))+(((-1.0)*(gconst16*gconst16))))),-1);
16404 if(!x1305.valid){
16405 continue;
16406 }
16407 CheckValue<IkReal> x1306 = IKatan2WithCheck(IkReal((gconst16*new_r00)),IkReal((gconst17*new_r00)),IKFAST_ATAN2_MAGTHRESH);
16408 if(!x1306.valid){
16409 continue;
16410 }
16411 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1305.value)))+(x1306.value));
16412 sj3array[0]=IKsin(j3array[0]);
16413 cj3array[0]=IKcos(j3array[0]);
16414 if( j3array[0] > IKPI )
16415 {
16416  j3array[0]-=IK2PI;
16417 }
16418 else if( j3array[0] < -IKPI )
16419 { j3array[0]+=IK2PI;
16420 }
16421 j3valid[0] = true;
16422 for(int ij3 = 0; ij3 < 1; ++ij3)
16423 {
16424 if( !j3valid[ij3] )
16425 {
16426  continue;
16427 }
16428 _ij3[0] = ij3; _ij3[1] = -1;
16429 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16430 {
16431 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16432 {
16433  j3valid[iij3]=false; _ij3[1] = iij3; break;
16434 }
16435 }
16436 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16437 {
16438 IkReal evalcond[6];
16439 IkReal x1307=IKsin(j3);
16440 IkReal x1308=IKcos(j3);
16441 IkReal x1309=(gconst17*x1307);
16442 IkReal x1310=(gconst16*x1307);
16443 IkReal x1311=(gconst17*x1308);
16444 IkReal x1312=((1.0)*x1308);
16445 IkReal x1313=(gconst16*x1312);
16446 evalcond[0]=(x1309+(((-1.0)*x1313)));
16447 evalcond[1]=(gconst17+((new_r10*x1307))+((new_r00*x1308)));
16448 evalcond[2]=(x1311+x1310+new_r00);
16449 evalcond[3]=((((-1.0)*new_r10*x1312))+gconst16+((new_r00*x1307)));
16450 evalcond[4]=((((-1.0)*x1310))+(((-1.0)*x1311)));
16451 evalcond[5]=(x1309+(((-1.0)*x1313))+new_r10);
16452 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16453 {
16454 continue;
16455 }
16456 }
16457 
16458 {
16459 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16460 vinfos[0].jointtype = 1;
16461 vinfos[0].foffset = j0;
16462 vinfos[0].indices[0] = _ij0[0];
16463 vinfos[0].indices[1] = _ij0[1];
16464 vinfos[0].maxsolutions = _nj0;
16465 vinfos[1].jointtype = 1;
16466 vinfos[1].foffset = j1;
16467 vinfos[1].indices[0] = _ij1[0];
16468 vinfos[1].indices[1] = _ij1[1];
16469 vinfos[1].maxsolutions = _nj1;
16470 vinfos[2].jointtype = 1;
16471 vinfos[2].foffset = j2;
16472 vinfos[2].indices[0] = _ij2[0];
16473 vinfos[2].indices[1] = _ij2[1];
16474 vinfos[2].maxsolutions = _nj2;
16475 vinfos[3].jointtype = 1;
16476 vinfos[3].foffset = j3;
16477 vinfos[3].indices[0] = _ij3[0];
16478 vinfos[3].indices[1] = _ij3[1];
16479 vinfos[3].maxsolutions = _nj3;
16480 vinfos[4].jointtype = 1;
16481 vinfos[4].foffset = j4;
16482 vinfos[4].indices[0] = _ij4[0];
16483 vinfos[4].indices[1] = _ij4[1];
16484 vinfos[4].maxsolutions = _nj4;
16485 vinfos[5].jointtype = 1;
16486 vinfos[5].foffset = j5;
16487 vinfos[5].indices[0] = _ij5[0];
16488 vinfos[5].indices[1] = _ij5[1];
16489 vinfos[5].maxsolutions = _nj5;
16490 std::vector<int> vfree(0);
16491 solutions.AddSolution(vinfos,vfree);
16492 }
16493 }
16494 }
16495 
16496 }
16497 
16498 }
16499 
16500 } else
16501 {
16502 {
16503 IkReal j3array[1], cj3array[1], sj3array[1];
16504 bool j3valid[1]={false};
16505 _nj3 = 1;
16506 CheckValue<IkReal> x1314=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst16*new_r00))+((gconst17*new_r10)))),-1);
16507 if(!x1314.valid){
16508 continue;
16509 }
16510 CheckValue<IkReal> x1315 = IKatan2WithCheck(IkReal(gconst16*gconst16),IkReal((gconst16*gconst17)),IKFAST_ATAN2_MAGTHRESH);
16511 if(!x1315.valid){
16512 continue;
16513 }
16514 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1314.value)))+(x1315.value));
16515 sj3array[0]=IKsin(j3array[0]);
16516 cj3array[0]=IKcos(j3array[0]);
16517 if( j3array[0] > IKPI )
16518 {
16519  j3array[0]-=IK2PI;
16520 }
16521 else if( j3array[0] < -IKPI )
16522 { j3array[0]+=IK2PI;
16523 }
16524 j3valid[0] = true;
16525 for(int ij3 = 0; ij3 < 1; ++ij3)
16526 {
16527 if( !j3valid[ij3] )
16528 {
16529  continue;
16530 }
16531 _ij3[0] = ij3; _ij3[1] = -1;
16532 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16533 {
16534 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16535 {
16536  j3valid[iij3]=false; _ij3[1] = iij3; break;
16537 }
16538 }
16539 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16540 {
16541 IkReal evalcond[6];
16542 IkReal x1316=IKsin(j3);
16543 IkReal x1317=IKcos(j3);
16544 IkReal x1318=(gconst17*x1316);
16545 IkReal x1319=(gconst16*x1316);
16546 IkReal x1320=(gconst17*x1317);
16547 IkReal x1321=((1.0)*x1317);
16548 IkReal x1322=(gconst16*x1321);
16549 evalcond[0]=(x1318+(((-1.0)*x1322)));
16550 evalcond[1]=(((new_r00*x1317))+gconst17+((new_r10*x1316)));
16551 evalcond[2]=(x1319+x1320+new_r00);
16552 evalcond[3]=(((new_r00*x1316))+(((-1.0)*new_r10*x1321))+gconst16);
16553 evalcond[4]=((((-1.0)*x1319))+(((-1.0)*x1320)));
16554 evalcond[5]=(x1318+(((-1.0)*x1322))+new_r10);
16555 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16556 {
16557 continue;
16558 }
16559 }
16560 
16561 {
16562 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16563 vinfos[0].jointtype = 1;
16564 vinfos[0].foffset = j0;
16565 vinfos[0].indices[0] = _ij0[0];
16566 vinfos[0].indices[1] = _ij0[1];
16567 vinfos[0].maxsolutions = _nj0;
16568 vinfos[1].jointtype = 1;
16569 vinfos[1].foffset = j1;
16570 vinfos[1].indices[0] = _ij1[0];
16571 vinfos[1].indices[1] = _ij1[1];
16572 vinfos[1].maxsolutions = _nj1;
16573 vinfos[2].jointtype = 1;
16574 vinfos[2].foffset = j2;
16575 vinfos[2].indices[0] = _ij2[0];
16576 vinfos[2].indices[1] = _ij2[1];
16577 vinfos[2].maxsolutions = _nj2;
16578 vinfos[3].jointtype = 1;
16579 vinfos[3].foffset = j3;
16580 vinfos[3].indices[0] = _ij3[0];
16581 vinfos[3].indices[1] = _ij3[1];
16582 vinfos[3].maxsolutions = _nj3;
16583 vinfos[4].jointtype = 1;
16584 vinfos[4].foffset = j4;
16585 vinfos[4].indices[0] = _ij4[0];
16586 vinfos[4].indices[1] = _ij4[1];
16587 vinfos[4].maxsolutions = _nj4;
16588 vinfos[5].jointtype = 1;
16589 vinfos[5].foffset = j5;
16590 vinfos[5].indices[0] = _ij5[0];
16591 vinfos[5].indices[1] = _ij5[1];
16592 vinfos[5].maxsolutions = _nj5;
16593 std::vector<int> vfree(0);
16594 solutions.AddSolution(vinfos,vfree);
16595 }
16596 }
16597 }
16598 
16599 }
16600 
16601 }
16602 
16603 }
16604 } while(0);
16605 if( bgotonextstatement )
16606 {
16607 bool bgotonextstatement = true;
16608 do
16609 {
16610 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
16611 if( IKabs(evalcond[0]) < 0.0000050000000000 )
16612 {
16613 bgotonextstatement=false;
16614 {
16615 IkReal j3array[2], cj3array[2], sj3array[2];
16616 bool j3valid[2]={false};
16617 _nj3 = 2;
16618 CheckValue<IkReal> x1323=IKPowWithIntegerCheck(gconst16,-1);
16619 if(!x1323.valid){
16620 continue;
16621 }
16622 sj3array[0]=(new_r11*(x1323.value));
16623 if( sj3array[0] >= -1-IKFAST_SINCOS_THRESH && sj3array[0] <= 1+IKFAST_SINCOS_THRESH )
16624 {
16625  j3valid[0] = j3valid[1] = true;
16626  j3array[0] = IKasin(sj3array[0]);
16627  cj3array[0] = IKcos(j3array[0]);
16628  sj3array[1] = sj3array[0];
16629  j3array[1] = j3array[0] > 0 ? (IKPI-j3array[0]) : (-IKPI-j3array[0]);
16630  cj3array[1] = -cj3array[0];
16631 }
16632 else if( isnan(sj3array[0]) )
16633 {
16634  // probably any value will work
16635  j3valid[0] = true;
16636  cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
16637 }
16638 for(int ij3 = 0; ij3 < 2; ++ij3)
16639 {
16640 if( !j3valid[ij3] )
16641 {
16642  continue;
16643 }
16644 _ij3[0] = ij3; _ij3[1] = -1;
16645 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
16646 {
16647 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16648 {
16649  j3valid[iij3]=false; _ij3[1] = iij3; break;
16650 }
16651 }
16652 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16653 {
16654 IkReal evalcond[6];
16655 IkReal x1324=IKcos(j3);
16656 IkReal x1325=IKsin(j3);
16657 IkReal x1326=((-1.0)*x1324);
16658 evalcond[0]=(new_r00*x1324);
16659 evalcond[1]=(new_r11*x1326);
16660 evalcond[2]=(gconst16*x1326);
16661 evalcond[3]=(((new_r00*x1325))+gconst16);
16662 evalcond[4]=(((gconst16*x1325))+new_r00);
16663 evalcond[5]=(((new_r11*x1325))+(((-1.0)*gconst16)));
16664 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16665 {
16666 continue;
16667 }
16668 }
16669 
16670 {
16671 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16672 vinfos[0].jointtype = 1;
16673 vinfos[0].foffset = j0;
16674 vinfos[0].indices[0] = _ij0[0];
16675 vinfos[0].indices[1] = _ij0[1];
16676 vinfos[0].maxsolutions = _nj0;
16677 vinfos[1].jointtype = 1;
16678 vinfos[1].foffset = j1;
16679 vinfos[1].indices[0] = _ij1[0];
16680 vinfos[1].indices[1] = _ij1[1];
16681 vinfos[1].maxsolutions = _nj1;
16682 vinfos[2].jointtype = 1;
16683 vinfos[2].foffset = j2;
16684 vinfos[2].indices[0] = _ij2[0];
16685 vinfos[2].indices[1] = _ij2[1];
16686 vinfos[2].maxsolutions = _nj2;
16687 vinfos[3].jointtype = 1;
16688 vinfos[3].foffset = j3;
16689 vinfos[3].indices[0] = _ij3[0];
16690 vinfos[3].indices[1] = _ij3[1];
16691 vinfos[3].maxsolutions = _nj3;
16692 vinfos[4].jointtype = 1;
16693 vinfos[4].foffset = j4;
16694 vinfos[4].indices[0] = _ij4[0];
16695 vinfos[4].indices[1] = _ij4[1];
16696 vinfos[4].maxsolutions = _nj4;
16697 vinfos[5].jointtype = 1;
16698 vinfos[5].foffset = j5;
16699 vinfos[5].indices[0] = _ij5[0];
16700 vinfos[5].indices[1] = _ij5[1];
16701 vinfos[5].maxsolutions = _nj5;
16702 std::vector<int> vfree(0);
16703 solutions.AddSolution(vinfos,vfree);
16704 }
16705 }
16706 }
16707 
16708 }
16709 } while(0);
16710 if( bgotonextstatement )
16711 {
16712 bool bgotonextstatement = true;
16713 do
16714 {
16715 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
16716 if( IKabs(evalcond[0]) < 0.0000050000000000 )
16717 {
16718 bgotonextstatement=false;
16719 {
16720 IkReal j3eval[1];
16721 IkReal x1327=((-1.0)*new_r00);
16722 CheckValue<IkReal> x1329 = IKatan2WithCheck(IkReal(x1327),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
16723 if(!x1329.valid){
16724 continue;
16725 }
16726 IkReal x1328=((1.0)*(x1329.value));
16727 sj4=0;
16728 cj4=-1.0;
16729 j4=3.14159265358979;
16730 sj5=gconst16;
16731 cj5=gconst17;
16732 j5=((3.14159265)+(((-1.0)*x1328)));
16733 new_r11=0;
16734 new_r10=0;
16735 new_r22=0;
16736 new_r02=0;
16737 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1328)));
16738 IkReal x1330 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
16739 if(IKabs(x1330)==0){
16740 continue;
16741 }
16742 IkReal gconst16=(x1327*(pow(x1330,-0.5)));
16743 IkReal gconst17=0;
16744 j3eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
16745 if( IKabs(j3eval[0]) < 0.0000010000000000 )
16746 {
16747 {
16748 IkReal j3eval[1];
16749 IkReal x1331=((-1.0)*new_r00);
16750 CheckValue<IkReal> x1333 = IKatan2WithCheck(IkReal(x1331),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
16751 if(!x1333.valid){
16752 continue;
16753 }
16754 IkReal x1332=((1.0)*(x1333.value));
16755 sj4=0;
16756 cj4=-1.0;
16757 j4=3.14159265358979;
16758 sj5=gconst16;
16759 cj5=gconst17;
16760 j5=((3.14159265)+(((-1.0)*x1332)));
16761 new_r11=0;
16762 new_r10=0;
16763 new_r22=0;
16764 new_r02=0;
16765 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1332)));
16766 IkReal x1334 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
16767 if(IKabs(x1334)==0){
16768 continue;
16769 }
16770 IkReal gconst16=(x1331*(pow(x1334,-0.5)));
16771 IkReal gconst17=0;
16772 j3eval[0]=new_r00;
16773 if( IKabs(j3eval[0]) < 0.0000010000000000 )
16774 {
16775 {
16776 IkReal j3eval[2];
16777 IkReal x1335=((-1.0)*new_r00);
16778 CheckValue<IkReal> x1337 = IKatan2WithCheck(IkReal(x1335),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
16779 if(!x1337.valid){
16780 continue;
16781 }
16782 IkReal x1336=((1.0)*(x1337.value));
16783 sj4=0;
16784 cj4=-1.0;
16785 j4=3.14159265358979;
16786 sj5=gconst16;
16787 cj5=gconst17;
16788 j5=((3.14159265)+(((-1.0)*x1336)));
16789 new_r11=0;
16790 new_r10=0;
16791 new_r22=0;
16792 new_r02=0;
16793 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1336)));
16794 IkReal x1338 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
16795 if(IKabs(x1338)==0){
16796 continue;
16797 }
16798 IkReal gconst16=(x1335*(pow(x1338,-0.5)));
16799 IkReal gconst17=0;
16800 j3eval[0]=new_r00;
16801 j3eval[1]=new_r01;
16802 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
16803 {
16804 continue; // 3 cases reached
16805 
16806 } else
16807 {
16808 {
16809 IkReal j3array[1], cj3array[1], sj3array[1];
16810 bool j3valid[1]={false};
16811 _nj3 = 1;
16812 CheckValue<IkReal> x1339=IKPowWithIntegerCheck(new_r00,-1);
16813 if(!x1339.valid){
16814 continue;
16815 }
16816 CheckValue<IkReal> x1340=IKPowWithIntegerCheck(new_r01,-1);
16817 if(!x1340.valid){
16818 continue;
16819 }
16820 if( IKabs(((-1.0)*gconst16*(x1339.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst16*(x1340.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst16*(x1339.value)))+IKsqr((gconst16*(x1340.value)))-1) <= IKFAST_SINCOS_THRESH )
16821  continue;
16822 j3array[0]=IKatan2(((-1.0)*gconst16*(x1339.value)), (gconst16*(x1340.value)));
16823 sj3array[0]=IKsin(j3array[0]);
16824 cj3array[0]=IKcos(j3array[0]);
16825 if( j3array[0] > IKPI )
16826 {
16827  j3array[0]-=IK2PI;
16828 }
16829 else if( j3array[0] < -IKPI )
16830 { j3array[0]+=IK2PI;
16831 }
16832 j3valid[0] = true;
16833 for(int ij3 = 0; ij3 < 1; ++ij3)
16834 {
16835 if( !j3valid[ij3] )
16836 {
16837  continue;
16838 }
16839 _ij3[0] = ij3; _ij3[1] = -1;
16840 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16841 {
16842 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16843 {
16844  j3valid[iij3]=false; _ij3[1] = iij3; break;
16845 }
16846 }
16847 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16848 {
16849 IkReal evalcond[8];
16850 IkReal x1341=IKsin(j3);
16851 IkReal x1342=IKcos(j3);
16852 IkReal x1343=((1.0)*gconst16);
16853 IkReal x1344=((-1.0)*gconst16);
16854 evalcond[0]=(new_r01*x1341);
16855 evalcond[1]=(new_r00*x1342);
16856 evalcond[2]=(x1341*x1344);
16857 evalcond[3]=(x1342*x1344);
16858 evalcond[4]=(gconst16+((new_r00*x1341)));
16859 evalcond[5]=(((gconst16*x1341))+new_r00);
16860 evalcond[6]=((((-1.0)*x1342*x1343))+new_r01);
16861 evalcond[7]=((((-1.0)*x1343))+((new_r01*x1342)));
16862 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
16863 {
16864 continue;
16865 }
16866 }
16867 
16868 {
16869 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16870 vinfos[0].jointtype = 1;
16871 vinfos[0].foffset = j0;
16872 vinfos[0].indices[0] = _ij0[0];
16873 vinfos[0].indices[1] = _ij0[1];
16874 vinfos[0].maxsolutions = _nj0;
16875 vinfos[1].jointtype = 1;
16876 vinfos[1].foffset = j1;
16877 vinfos[1].indices[0] = _ij1[0];
16878 vinfos[1].indices[1] = _ij1[1];
16879 vinfos[1].maxsolutions = _nj1;
16880 vinfos[2].jointtype = 1;
16881 vinfos[2].foffset = j2;
16882 vinfos[2].indices[0] = _ij2[0];
16883 vinfos[2].indices[1] = _ij2[1];
16884 vinfos[2].maxsolutions = _nj2;
16885 vinfos[3].jointtype = 1;
16886 vinfos[3].foffset = j3;
16887 vinfos[3].indices[0] = _ij3[0];
16888 vinfos[3].indices[1] = _ij3[1];
16889 vinfos[3].maxsolutions = _nj3;
16890 vinfos[4].jointtype = 1;
16891 vinfos[4].foffset = j4;
16892 vinfos[4].indices[0] = _ij4[0];
16893 vinfos[4].indices[1] = _ij4[1];
16894 vinfos[4].maxsolutions = _nj4;
16895 vinfos[5].jointtype = 1;
16896 vinfos[5].foffset = j5;
16897 vinfos[5].indices[0] = _ij5[0];
16898 vinfos[5].indices[1] = _ij5[1];
16899 vinfos[5].maxsolutions = _nj5;
16900 std::vector<int> vfree(0);
16901 solutions.AddSolution(vinfos,vfree);
16902 }
16903 }
16904 }
16905 
16906 }
16907 
16908 }
16909 
16910 } else
16911 {
16912 {
16913 IkReal j3array[1], cj3array[1], sj3array[1];
16914 bool j3valid[1]={false};
16915 _nj3 = 1;
16916 CheckValue<IkReal> x1345=IKPowWithIntegerCheck(new_r00,-1);
16917 if(!x1345.valid){
16918 continue;
16919 }
16920 CheckValue<IkReal> x1346=IKPowWithIntegerCheck(gconst16,-1);
16921 if(!x1346.valid){
16922 continue;
16923 }
16924 if( IKabs(((-1.0)*gconst16*(x1345.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1346.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst16*(x1345.value)))+IKsqr((new_r01*(x1346.value)))-1) <= IKFAST_SINCOS_THRESH )
16925  continue;
16926 j3array[0]=IKatan2(((-1.0)*gconst16*(x1345.value)), (new_r01*(x1346.value)));
16927 sj3array[0]=IKsin(j3array[0]);
16928 cj3array[0]=IKcos(j3array[0]);
16929 if( j3array[0] > IKPI )
16930 {
16931  j3array[0]-=IK2PI;
16932 }
16933 else if( j3array[0] < -IKPI )
16934 { j3array[0]+=IK2PI;
16935 }
16936 j3valid[0] = true;
16937 for(int ij3 = 0; ij3 < 1; ++ij3)
16938 {
16939 if( !j3valid[ij3] )
16940 {
16941  continue;
16942 }
16943 _ij3[0] = ij3; _ij3[1] = -1;
16944 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16945 {
16946 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16947 {
16948  j3valid[iij3]=false; _ij3[1] = iij3; break;
16949 }
16950 }
16951 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16952 {
16953 IkReal evalcond[8];
16954 IkReal x1347=IKsin(j3);
16955 IkReal x1348=IKcos(j3);
16956 IkReal x1349=((1.0)*gconst16);
16957 IkReal x1350=((-1.0)*gconst16);
16958 evalcond[0]=(new_r01*x1347);
16959 evalcond[1]=(new_r00*x1348);
16960 evalcond[2]=(x1347*x1350);
16961 evalcond[3]=(x1348*x1350);
16962 evalcond[4]=(gconst16+((new_r00*x1347)));
16963 evalcond[5]=(((gconst16*x1347))+new_r00);
16964 evalcond[6]=((((-1.0)*x1348*x1349))+new_r01);
16965 evalcond[7]=((((-1.0)*x1349))+((new_r01*x1348)));
16966 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
16967 {
16968 continue;
16969 }
16970 }
16971 
16972 {
16973 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16974 vinfos[0].jointtype = 1;
16975 vinfos[0].foffset = j0;
16976 vinfos[0].indices[0] = _ij0[0];
16977 vinfos[0].indices[1] = _ij0[1];
16978 vinfos[0].maxsolutions = _nj0;
16979 vinfos[1].jointtype = 1;
16980 vinfos[1].foffset = j1;
16981 vinfos[1].indices[0] = _ij1[0];
16982 vinfos[1].indices[1] = _ij1[1];
16983 vinfos[1].maxsolutions = _nj1;
16984 vinfos[2].jointtype = 1;
16985 vinfos[2].foffset = j2;
16986 vinfos[2].indices[0] = _ij2[0];
16987 vinfos[2].indices[1] = _ij2[1];
16988 vinfos[2].maxsolutions = _nj2;
16989 vinfos[3].jointtype = 1;
16990 vinfos[3].foffset = j3;
16991 vinfos[3].indices[0] = _ij3[0];
16992 vinfos[3].indices[1] = _ij3[1];
16993 vinfos[3].maxsolutions = _nj3;
16994 vinfos[4].jointtype = 1;
16995 vinfos[4].foffset = j4;
16996 vinfos[4].indices[0] = _ij4[0];
16997 vinfos[4].indices[1] = _ij4[1];
16998 vinfos[4].maxsolutions = _nj4;
16999 vinfos[5].jointtype = 1;
17000 vinfos[5].foffset = j5;
17001 vinfos[5].indices[0] = _ij5[0];
17002 vinfos[5].indices[1] = _ij5[1];
17003 vinfos[5].maxsolutions = _nj5;
17004 std::vector<int> vfree(0);
17005 solutions.AddSolution(vinfos,vfree);
17006 }
17007 }
17008 }
17009 
17010 }
17011 
17012 }
17013 
17014 } else
17015 {
17016 {
17017 IkReal j3array[1], cj3array[1], sj3array[1];
17018 bool j3valid[1]={false};
17019 _nj3 = 1;
17020 CheckValue<IkReal> x1351 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
17021 if(!x1351.valid){
17022 continue;
17023 }
17024 CheckValue<IkReal> x1352=IKPowWithIntegerCheck(IKsign(gconst16),-1);
17025 if(!x1352.valid){
17026 continue;
17027 }
17028 j3array[0]=((-1.5707963267949)+(x1351.value)+(((1.5707963267949)*(x1352.value))));
17029 sj3array[0]=IKsin(j3array[0]);
17030 cj3array[0]=IKcos(j3array[0]);
17031 if( j3array[0] > IKPI )
17032 {
17033  j3array[0]-=IK2PI;
17034 }
17035 else if( j3array[0] < -IKPI )
17036 { j3array[0]+=IK2PI;
17037 }
17038 j3valid[0] = true;
17039 for(int ij3 = 0; ij3 < 1; ++ij3)
17040 {
17041 if( !j3valid[ij3] )
17042 {
17043  continue;
17044 }
17045 _ij3[0] = ij3; _ij3[1] = -1;
17046 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17047 {
17048 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17049 {
17050  j3valid[iij3]=false; _ij3[1] = iij3; break;
17051 }
17052 }
17053 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17054 {
17055 IkReal evalcond[8];
17056 IkReal x1353=IKsin(j3);
17057 IkReal x1354=IKcos(j3);
17058 IkReal x1355=((1.0)*gconst16);
17059 IkReal x1356=((-1.0)*gconst16);
17060 evalcond[0]=(new_r01*x1353);
17061 evalcond[1]=(new_r00*x1354);
17062 evalcond[2]=(x1353*x1356);
17063 evalcond[3]=(x1354*x1356);
17064 evalcond[4]=(gconst16+((new_r00*x1353)));
17065 evalcond[5]=(new_r00+((gconst16*x1353)));
17066 evalcond[6]=((((-1.0)*x1354*x1355))+new_r01);
17067 evalcond[7]=((((-1.0)*x1355))+((new_r01*x1354)));
17068 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17069 {
17070 continue;
17071 }
17072 }
17073 
17074 {
17075 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17076 vinfos[0].jointtype = 1;
17077 vinfos[0].foffset = j0;
17078 vinfos[0].indices[0] = _ij0[0];
17079 vinfos[0].indices[1] = _ij0[1];
17080 vinfos[0].maxsolutions = _nj0;
17081 vinfos[1].jointtype = 1;
17082 vinfos[1].foffset = j1;
17083 vinfos[1].indices[0] = _ij1[0];
17084 vinfos[1].indices[1] = _ij1[1];
17085 vinfos[1].maxsolutions = _nj1;
17086 vinfos[2].jointtype = 1;
17087 vinfos[2].foffset = j2;
17088 vinfos[2].indices[0] = _ij2[0];
17089 vinfos[2].indices[1] = _ij2[1];
17090 vinfos[2].maxsolutions = _nj2;
17091 vinfos[3].jointtype = 1;
17092 vinfos[3].foffset = j3;
17093 vinfos[3].indices[0] = _ij3[0];
17094 vinfos[3].indices[1] = _ij3[1];
17095 vinfos[3].maxsolutions = _nj3;
17096 vinfos[4].jointtype = 1;
17097 vinfos[4].foffset = j4;
17098 vinfos[4].indices[0] = _ij4[0];
17099 vinfos[4].indices[1] = _ij4[1];
17100 vinfos[4].maxsolutions = _nj4;
17101 vinfos[5].jointtype = 1;
17102 vinfos[5].foffset = j5;
17103 vinfos[5].indices[0] = _ij5[0];
17104 vinfos[5].indices[1] = _ij5[1];
17105 vinfos[5].maxsolutions = _nj5;
17106 std::vector<int> vfree(0);
17107 solutions.AddSolution(vinfos,vfree);
17108 }
17109 }
17110 }
17111 
17112 }
17113 
17114 }
17115 
17116 }
17117 } while(0);
17118 if( bgotonextstatement )
17119 {
17120 bool bgotonextstatement = true;
17121 do
17122 {
17123 evalcond[0]=IKabs(new_r10);
17124 if( IKabs(evalcond[0]) < 0.0000050000000000 )
17125 {
17126 bgotonextstatement=false;
17127 {
17128 IkReal j3eval[1];
17129 IkReal x1357=((-1.0)*new_r00);
17130 CheckValue<IkReal> x1359 = IKatan2WithCheck(IkReal(x1357),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
17131 if(!x1359.valid){
17132 continue;
17133 }
17134 IkReal x1358=((1.0)*(x1359.value));
17135 sj4=0;
17136 cj4=-1.0;
17137 j4=3.14159265358979;
17138 sj5=gconst16;
17139 cj5=gconst17;
17140 j5=((3.14159265)+(((-1.0)*x1358)));
17141 new_r10=0;
17142 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1358)));
17143 IkReal x1360 = new_r00*new_r00;
17144 if(IKabs(x1360)==0){
17145 continue;
17146 }
17147 IkReal gconst16=(x1357*(pow(x1360,-0.5)));
17148 IkReal gconst17=0;
17149 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
17150 if( IKabs(j3eval[0]) < 0.0000010000000000 )
17151 {
17152 {
17153 IkReal j3eval[1];
17154 IkReal x1361=((-1.0)*new_r00);
17155 CheckValue<IkReal> x1363 = IKatan2WithCheck(IkReal(x1361),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
17156 if(!x1363.valid){
17157 continue;
17158 }
17159 IkReal x1362=((1.0)*(x1363.value));
17160 sj4=0;
17161 cj4=-1.0;
17162 j4=3.14159265358979;
17163 sj5=gconst16;
17164 cj5=gconst17;
17165 j5=((3.14159265)+(((-1.0)*x1362)));
17166 new_r10=0;
17167 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1362)));
17168 IkReal x1364 = new_r00*new_r00;
17169 if(IKabs(x1364)==0){
17170 continue;
17171 }
17172 IkReal gconst16=(x1361*(pow(x1364,-0.5)));
17173 IkReal gconst17=0;
17174 j3eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
17175 if( IKabs(j3eval[0]) < 0.0000010000000000 )
17176 {
17177 {
17178 IkReal j3eval[1];
17179 IkReal x1365=((-1.0)*new_r00);
17180 CheckValue<IkReal> x1367 = IKatan2WithCheck(IkReal(x1365),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
17181 if(!x1367.valid){
17182 continue;
17183 }
17184 IkReal x1366=((1.0)*(x1367.value));
17185 sj4=0;
17186 cj4=-1.0;
17187 j4=3.14159265358979;
17188 sj5=gconst16;
17189 cj5=gconst17;
17190 j5=((3.14159265)+(((-1.0)*x1366)));
17191 new_r10=0;
17192 IkReal gconst15=((3.14159265358979)+(((-1.0)*x1366)));
17193 IkReal x1368 = new_r00*new_r00;
17194 if(IKabs(x1368)==0){
17195 continue;
17196 }
17197 IkReal gconst16=(x1365*(pow(x1368,-0.5)));
17198 IkReal gconst17=0;
17199 j3eval[0]=new_r00;
17200 if( IKabs(j3eval[0]) < 0.0000010000000000 )
17201 {
17202 continue; // 3 cases reached
17203 
17204 } else
17205 {
17206 {
17207 IkReal j3array[1], cj3array[1], sj3array[1];
17208 bool j3valid[1]={false};
17209 _nj3 = 1;
17210 CheckValue<IkReal> x1369=IKPowWithIntegerCheck(new_r00,-1);
17211 if(!x1369.valid){
17212 continue;
17213 }
17214 CheckValue<IkReal> x1370=IKPowWithIntegerCheck(gconst16,-1);
17215 if(!x1370.valid){
17216 continue;
17217 }
17218 if( IKabs(((-1.0)*gconst16*(x1369.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1370.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst16*(x1369.value)))+IKsqr((new_r01*(x1370.value)))-1) <= IKFAST_SINCOS_THRESH )
17219  continue;
17220 j3array[0]=IKatan2(((-1.0)*gconst16*(x1369.value)), (new_r01*(x1370.value)));
17221 sj3array[0]=IKsin(j3array[0]);
17222 cj3array[0]=IKcos(j3array[0]);
17223 if( j3array[0] > IKPI )
17224 {
17225  j3array[0]-=IK2PI;
17226 }
17227 else if( j3array[0] < -IKPI )
17228 { j3array[0]+=IK2PI;
17229 }
17230 j3valid[0] = true;
17231 for(int ij3 = 0; ij3 < 1; ++ij3)
17232 {
17233 if( !j3valid[ij3] )
17234 {
17235  continue;
17236 }
17237 _ij3[0] = ij3; _ij3[1] = -1;
17238 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17239 {
17240 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17241 {
17242  j3valid[iij3]=false; _ij3[1] = iij3; break;
17243 }
17244 }
17245 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17246 {
17247 IkReal evalcond[8];
17248 IkReal x1371=IKcos(j3);
17249 IkReal x1372=IKsin(j3);
17250 IkReal x1373=((1.0)*gconst16);
17251 evalcond[0]=(new_r00*x1371);
17252 evalcond[1]=((-1.0)*gconst16*x1371);
17253 evalcond[2]=(gconst16+((new_r00*x1372)));
17254 evalcond[3]=(new_r00+((gconst16*x1372)));
17255 evalcond[4]=((((-1.0)*x1371*x1373))+new_r01);
17256 evalcond[5]=((((-1.0)*x1372*x1373))+new_r11);
17257 evalcond[6]=(((new_r01*x1372))+(((-1.0)*new_r11*x1371)));
17258 evalcond[7]=((((-1.0)*x1373))+((new_r11*x1372))+((new_r01*x1371)));
17259 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17260 {
17261 continue;
17262 }
17263 }
17264 
17265 {
17266 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17267 vinfos[0].jointtype = 1;
17268 vinfos[0].foffset = j0;
17269 vinfos[0].indices[0] = _ij0[0];
17270 vinfos[0].indices[1] = _ij0[1];
17271 vinfos[0].maxsolutions = _nj0;
17272 vinfos[1].jointtype = 1;
17273 vinfos[1].foffset = j1;
17274 vinfos[1].indices[0] = _ij1[0];
17275 vinfos[1].indices[1] = _ij1[1];
17276 vinfos[1].maxsolutions = _nj1;
17277 vinfos[2].jointtype = 1;
17278 vinfos[2].foffset = j2;
17279 vinfos[2].indices[0] = _ij2[0];
17280 vinfos[2].indices[1] = _ij2[1];
17281 vinfos[2].maxsolutions = _nj2;
17282 vinfos[3].jointtype = 1;
17283 vinfos[3].foffset = j3;
17284 vinfos[3].indices[0] = _ij3[0];
17285 vinfos[3].indices[1] = _ij3[1];
17286 vinfos[3].maxsolutions = _nj3;
17287 vinfos[4].jointtype = 1;
17288 vinfos[4].foffset = j4;
17289 vinfos[4].indices[0] = _ij4[0];
17290 vinfos[4].indices[1] = _ij4[1];
17291 vinfos[4].maxsolutions = _nj4;
17292 vinfos[5].jointtype = 1;
17293 vinfos[5].foffset = j5;
17294 vinfos[5].indices[0] = _ij5[0];
17295 vinfos[5].indices[1] = _ij5[1];
17296 vinfos[5].maxsolutions = _nj5;
17297 std::vector<int> vfree(0);
17298 solutions.AddSolution(vinfos,vfree);
17299 }
17300 }
17301 }
17302 
17303 }
17304 
17305 }
17306 
17307 } else
17308 {
17309 {
17310 IkReal j3array[1], cj3array[1], sj3array[1];
17311 bool j3valid[1]={false};
17312 _nj3 = 1;
17313 CheckValue<IkReal> x1374 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
17314 if(!x1374.valid){
17315 continue;
17316 }
17317 CheckValue<IkReal> x1375=IKPowWithIntegerCheck(IKsign(gconst16),-1);
17318 if(!x1375.valid){
17319 continue;
17320 }
17321 j3array[0]=((-1.5707963267949)+(x1374.value)+(((1.5707963267949)*(x1375.value))));
17322 sj3array[0]=IKsin(j3array[0]);
17323 cj3array[0]=IKcos(j3array[0]);
17324 if( j3array[0] > IKPI )
17325 {
17326  j3array[0]-=IK2PI;
17327 }
17328 else if( j3array[0] < -IKPI )
17329 { j3array[0]+=IK2PI;
17330 }
17331 j3valid[0] = true;
17332 for(int ij3 = 0; ij3 < 1; ++ij3)
17333 {
17334 if( !j3valid[ij3] )
17335 {
17336  continue;
17337 }
17338 _ij3[0] = ij3; _ij3[1] = -1;
17339 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17340 {
17341 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17342 {
17343  j3valid[iij3]=false; _ij3[1] = iij3; break;
17344 }
17345 }
17346 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17347 {
17348 IkReal evalcond[8];
17349 IkReal x1376=IKcos(j3);
17350 IkReal x1377=IKsin(j3);
17351 IkReal x1378=((1.0)*gconst16);
17352 evalcond[0]=(new_r00*x1376);
17353 evalcond[1]=((-1.0)*gconst16*x1376);
17354 evalcond[2]=(gconst16+((new_r00*x1377)));
17355 evalcond[3]=(new_r00+((gconst16*x1377)));
17356 evalcond[4]=((((-1.0)*x1376*x1378))+new_r01);
17357 evalcond[5]=((((-1.0)*x1377*x1378))+new_r11);
17358 evalcond[6]=(((new_r01*x1377))+(((-1.0)*new_r11*x1376)));
17359 evalcond[7]=((((-1.0)*x1378))+((new_r11*x1377))+((new_r01*x1376)));
17360 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17361 {
17362 continue;
17363 }
17364 }
17365 
17366 {
17367 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17368 vinfos[0].jointtype = 1;
17369 vinfos[0].foffset = j0;
17370 vinfos[0].indices[0] = _ij0[0];
17371 vinfos[0].indices[1] = _ij0[1];
17372 vinfos[0].maxsolutions = _nj0;
17373 vinfos[1].jointtype = 1;
17374 vinfos[1].foffset = j1;
17375 vinfos[1].indices[0] = _ij1[0];
17376 vinfos[1].indices[1] = _ij1[1];
17377 vinfos[1].maxsolutions = _nj1;
17378 vinfos[2].jointtype = 1;
17379 vinfos[2].foffset = j2;
17380 vinfos[2].indices[0] = _ij2[0];
17381 vinfos[2].indices[1] = _ij2[1];
17382 vinfos[2].maxsolutions = _nj2;
17383 vinfos[3].jointtype = 1;
17384 vinfos[3].foffset = j3;
17385 vinfos[3].indices[0] = _ij3[0];
17386 vinfos[3].indices[1] = _ij3[1];
17387 vinfos[3].maxsolutions = _nj3;
17388 vinfos[4].jointtype = 1;
17389 vinfos[4].foffset = j4;
17390 vinfos[4].indices[0] = _ij4[0];
17391 vinfos[4].indices[1] = _ij4[1];
17392 vinfos[4].maxsolutions = _nj4;
17393 vinfos[5].jointtype = 1;
17394 vinfos[5].foffset = j5;
17395 vinfos[5].indices[0] = _ij5[0];
17396 vinfos[5].indices[1] = _ij5[1];
17397 vinfos[5].maxsolutions = _nj5;
17398 std::vector<int> vfree(0);
17399 solutions.AddSolution(vinfos,vfree);
17400 }
17401 }
17402 }
17403 
17404 }
17405 
17406 }
17407 
17408 } else
17409 {
17410 {
17411 IkReal j3array[1], cj3array[1], sj3array[1];
17412 bool j3valid[1]={false};
17413 _nj3 = 1;
17414 CheckValue<IkReal> x1379=IKPowWithIntegerCheck(IKsign(gconst16),-1);
17415 if(!x1379.valid){
17416 continue;
17417 }
17418 CheckValue<IkReal> x1380 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
17419 if(!x1380.valid){
17420 continue;
17421 }
17422 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1379.value)))+(x1380.value));
17423 sj3array[0]=IKsin(j3array[0]);
17424 cj3array[0]=IKcos(j3array[0]);
17425 if( j3array[0] > IKPI )
17426 {
17427  j3array[0]-=IK2PI;
17428 }
17429 else if( j3array[0] < -IKPI )
17430 { j3array[0]+=IK2PI;
17431 }
17432 j3valid[0] = true;
17433 for(int ij3 = 0; ij3 < 1; ++ij3)
17434 {
17435 if( !j3valid[ij3] )
17436 {
17437  continue;
17438 }
17439 _ij3[0] = ij3; _ij3[1] = -1;
17440 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17441 {
17442 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17443 {
17444  j3valid[iij3]=false; _ij3[1] = iij3; break;
17445 }
17446 }
17447 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17448 {
17449 IkReal evalcond[8];
17450 IkReal x1381=IKcos(j3);
17451 IkReal x1382=IKsin(j3);
17452 IkReal x1383=((1.0)*gconst16);
17453 evalcond[0]=(new_r00*x1381);
17454 evalcond[1]=((-1.0)*gconst16*x1381);
17455 evalcond[2]=(gconst16+((new_r00*x1382)));
17456 evalcond[3]=(((gconst16*x1382))+new_r00);
17457 evalcond[4]=((((-1.0)*x1381*x1383))+new_r01);
17458 evalcond[5]=((((-1.0)*x1382*x1383))+new_r11);
17459 evalcond[6]=((((-1.0)*new_r11*x1381))+((new_r01*x1382)));
17460 evalcond[7]=((((-1.0)*x1383))+((new_r11*x1382))+((new_r01*x1381)));
17461 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17462 {
17463 continue;
17464 }
17465 }
17466 
17467 {
17468 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17469 vinfos[0].jointtype = 1;
17470 vinfos[0].foffset = j0;
17471 vinfos[0].indices[0] = _ij0[0];
17472 vinfos[0].indices[1] = _ij0[1];
17473 vinfos[0].maxsolutions = _nj0;
17474 vinfos[1].jointtype = 1;
17475 vinfos[1].foffset = j1;
17476 vinfos[1].indices[0] = _ij1[0];
17477 vinfos[1].indices[1] = _ij1[1];
17478 vinfos[1].maxsolutions = _nj1;
17479 vinfos[2].jointtype = 1;
17480 vinfos[2].foffset = j2;
17481 vinfos[2].indices[0] = _ij2[0];
17482 vinfos[2].indices[1] = _ij2[1];
17483 vinfos[2].maxsolutions = _nj2;
17484 vinfos[3].jointtype = 1;
17485 vinfos[3].foffset = j3;
17486 vinfos[3].indices[0] = _ij3[0];
17487 vinfos[3].indices[1] = _ij3[1];
17488 vinfos[3].maxsolutions = _nj3;
17489 vinfos[4].jointtype = 1;
17490 vinfos[4].foffset = j4;
17491 vinfos[4].indices[0] = _ij4[0];
17492 vinfos[4].indices[1] = _ij4[1];
17493 vinfos[4].maxsolutions = _nj4;
17494 vinfos[5].jointtype = 1;
17495 vinfos[5].foffset = j5;
17496 vinfos[5].indices[0] = _ij5[0];
17497 vinfos[5].indices[1] = _ij5[1];
17498 vinfos[5].maxsolutions = _nj5;
17499 std::vector<int> vfree(0);
17500 solutions.AddSolution(vinfos,vfree);
17501 }
17502 }
17503 }
17504 
17505 }
17506 
17507 }
17508 
17509 }
17510 } while(0);
17511 if( bgotonextstatement )
17512 {
17513 bool bgotonextstatement = true;
17514 do
17515 {
17516 if( 1 )
17517 {
17518 bgotonextstatement=false;
17519 continue; // branch miss [j3]
17520 
17521 }
17522 } while(0);
17523 if( bgotonextstatement )
17524 {
17525 }
17526 }
17527 }
17528 }
17529 }
17530 }
17531 }
17532 
17533 } else
17534 {
17535 {
17536 IkReal j3array[1], cj3array[1], sj3array[1];
17537 bool j3valid[1]={false};
17538 _nj3 = 1;
17539 IkReal x1384=((1.0)*gconst17);
17540 CheckValue<IkReal> x1385=IKPowWithIntegerCheck(IKsign((((gconst16*new_r00))+(((-1.0)*new_r10*x1384)))),-1);
17541 if(!x1385.valid){
17542 continue;
17543 }
17544 CheckValue<IkReal> x1386 = IKatan2WithCheck(IkReal(((((-1.0)*(new_r00*new_r00)))+(gconst17*gconst17))),IkReal((((new_r00*new_r10))+(((-1.0)*gconst16*x1384)))),IKFAST_ATAN2_MAGTHRESH);
17545 if(!x1386.valid){
17546 continue;
17547 }
17548 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1385.value)))+(x1386.value));
17549 sj3array[0]=IKsin(j3array[0]);
17550 cj3array[0]=IKcos(j3array[0]);
17551 if( j3array[0] > IKPI )
17552 {
17553  j3array[0]-=IK2PI;
17554 }
17555 else if( j3array[0] < -IKPI )
17556 { j3array[0]+=IK2PI;
17557 }
17558 j3valid[0] = true;
17559 for(int ij3 = 0; ij3 < 1; ++ij3)
17560 {
17561 if( !j3valid[ij3] )
17562 {
17563  continue;
17564 }
17565 _ij3[0] = ij3; _ij3[1] = -1;
17566 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17567 {
17568 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17569 {
17570  j3valid[iij3]=false; _ij3[1] = iij3; break;
17571 }
17572 }
17573 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17574 {
17575 IkReal evalcond[8];
17576 IkReal x1387=IKsin(j3);
17577 IkReal x1388=IKcos(j3);
17578 IkReal x1389=((1.0)*gconst16);
17579 IkReal x1390=(gconst17*x1387);
17580 IkReal x1391=(gconst17*x1388);
17581 IkReal x1392=((1.0)*x1388);
17582 IkReal x1393=(x1388*x1389);
17583 evalcond[0]=(((new_r10*x1387))+gconst17+((new_r00*x1388)));
17584 evalcond[1]=(x1391+((gconst16*x1387))+new_r00);
17585 evalcond[2]=(gconst16+((new_r00*x1387))+(((-1.0)*new_r10*x1392)));
17586 evalcond[3]=(gconst17+((new_r01*x1387))+(((-1.0)*new_r11*x1392)));
17587 evalcond[4]=(x1390+new_r01+(((-1.0)*x1393)));
17588 evalcond[5]=(x1390+new_r10+(((-1.0)*x1393)));
17589 evalcond[6]=((((-1.0)*x1389))+((new_r11*x1387))+((new_r01*x1388)));
17590 evalcond[7]=((((-1.0)*x1391))+new_r11+(((-1.0)*x1387*x1389)));
17591 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17592 {
17593 continue;
17594 }
17595 }
17596 
17597 {
17598 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17599 vinfos[0].jointtype = 1;
17600 vinfos[0].foffset = j0;
17601 vinfos[0].indices[0] = _ij0[0];
17602 vinfos[0].indices[1] = _ij0[1];
17603 vinfos[0].maxsolutions = _nj0;
17604 vinfos[1].jointtype = 1;
17605 vinfos[1].foffset = j1;
17606 vinfos[1].indices[0] = _ij1[0];
17607 vinfos[1].indices[1] = _ij1[1];
17608 vinfos[1].maxsolutions = _nj1;
17609 vinfos[2].jointtype = 1;
17610 vinfos[2].foffset = j2;
17611 vinfos[2].indices[0] = _ij2[0];
17612 vinfos[2].indices[1] = _ij2[1];
17613 vinfos[2].maxsolutions = _nj2;
17614 vinfos[3].jointtype = 1;
17615 vinfos[3].foffset = j3;
17616 vinfos[3].indices[0] = _ij3[0];
17617 vinfos[3].indices[1] = _ij3[1];
17618 vinfos[3].maxsolutions = _nj3;
17619 vinfos[4].jointtype = 1;
17620 vinfos[4].foffset = j4;
17621 vinfos[4].indices[0] = _ij4[0];
17622 vinfos[4].indices[1] = _ij4[1];
17623 vinfos[4].maxsolutions = _nj4;
17624 vinfos[5].jointtype = 1;
17625 vinfos[5].foffset = j5;
17626 vinfos[5].indices[0] = _ij5[0];
17627 vinfos[5].indices[1] = _ij5[1];
17628 vinfos[5].maxsolutions = _nj5;
17629 std::vector<int> vfree(0);
17630 solutions.AddSolution(vinfos,vfree);
17631 }
17632 }
17633 }
17634 
17635 }
17636 
17637 }
17638 
17639 } else
17640 {
17641 {
17642 IkReal j3array[1], cj3array[1], sj3array[1];
17643 bool j3valid[1]={false};
17644 _nj3 = 1;
17645 IkReal x1394=((1.0)*gconst17);
17646 CheckValue<IkReal> x1395=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst16*new_r11))+(((-1.0)*new_r01*x1394)))),-1);
17647 if(!x1395.valid){
17648 continue;
17649 }
17650 CheckValue<IkReal> x1396 = IKatan2WithCheck(IkReal((((new_r00*new_r11))+(gconst17*gconst17))),IkReal(((((-1.0)*gconst16*x1394))+((new_r00*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
17651 if(!x1396.valid){
17652 continue;
17653 }
17654 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1395.value)))+(x1396.value));
17655 sj3array[0]=IKsin(j3array[0]);
17656 cj3array[0]=IKcos(j3array[0]);
17657 if( j3array[0] > IKPI )
17658 {
17659  j3array[0]-=IK2PI;
17660 }
17661 else if( j3array[0] < -IKPI )
17662 { j3array[0]+=IK2PI;
17663 }
17664 j3valid[0] = true;
17665 for(int ij3 = 0; ij3 < 1; ++ij3)
17666 {
17667 if( !j3valid[ij3] )
17668 {
17669  continue;
17670 }
17671 _ij3[0] = ij3; _ij3[1] = -1;
17672 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17673 {
17674 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17675 {
17676  j3valid[iij3]=false; _ij3[1] = iij3; break;
17677 }
17678 }
17679 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17680 {
17681 IkReal evalcond[8];
17682 IkReal x1397=IKsin(j3);
17683 IkReal x1398=IKcos(j3);
17684 IkReal x1399=((1.0)*gconst16);
17685 IkReal x1400=(gconst17*x1397);
17686 IkReal x1401=(gconst17*x1398);
17687 IkReal x1402=((1.0)*x1398);
17688 IkReal x1403=(x1398*x1399);
17689 evalcond[0]=(((new_r10*x1397))+gconst17+((new_r00*x1398)));
17690 evalcond[1]=(x1401+new_r00+((gconst16*x1397)));
17691 evalcond[2]=(gconst16+((new_r00*x1397))+(((-1.0)*new_r10*x1402)));
17692 evalcond[3]=(gconst17+((new_r01*x1397))+(((-1.0)*new_r11*x1402)));
17693 evalcond[4]=((((-1.0)*x1403))+x1400+new_r01);
17694 evalcond[5]=((((-1.0)*x1403))+x1400+new_r10);
17695 evalcond[6]=(((new_r11*x1397))+((new_r01*x1398))+(((-1.0)*x1399)));
17696 evalcond[7]=((((-1.0)*x1401))+(((-1.0)*x1397*x1399))+new_r11);
17697 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17698 {
17699 continue;
17700 }
17701 }
17702 
17703 {
17704 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17705 vinfos[0].jointtype = 1;
17706 vinfos[0].foffset = j0;
17707 vinfos[0].indices[0] = _ij0[0];
17708 vinfos[0].indices[1] = _ij0[1];
17709 vinfos[0].maxsolutions = _nj0;
17710 vinfos[1].jointtype = 1;
17711 vinfos[1].foffset = j1;
17712 vinfos[1].indices[0] = _ij1[0];
17713 vinfos[1].indices[1] = _ij1[1];
17714 vinfos[1].maxsolutions = _nj1;
17715 vinfos[2].jointtype = 1;
17716 vinfos[2].foffset = j2;
17717 vinfos[2].indices[0] = _ij2[0];
17718 vinfos[2].indices[1] = _ij2[1];
17719 vinfos[2].maxsolutions = _nj2;
17720 vinfos[3].jointtype = 1;
17721 vinfos[3].foffset = j3;
17722 vinfos[3].indices[0] = _ij3[0];
17723 vinfos[3].indices[1] = _ij3[1];
17724 vinfos[3].maxsolutions = _nj3;
17725 vinfos[4].jointtype = 1;
17726 vinfos[4].foffset = j4;
17727 vinfos[4].indices[0] = _ij4[0];
17728 vinfos[4].indices[1] = _ij4[1];
17729 vinfos[4].maxsolutions = _nj4;
17730 vinfos[5].jointtype = 1;
17731 vinfos[5].foffset = j5;
17732 vinfos[5].indices[0] = _ij5[0];
17733 vinfos[5].indices[1] = _ij5[1];
17734 vinfos[5].maxsolutions = _nj5;
17735 std::vector<int> vfree(0);
17736 solutions.AddSolution(vinfos,vfree);
17737 }
17738 }
17739 }
17740 
17741 }
17742 
17743 }
17744 
17745 } else
17746 {
17747 {
17748 IkReal j3array[1], cj3array[1], sj3array[1];
17749 bool j3valid[1]={false};
17750 _nj3 = 1;
17751 IkReal x1404=((1.0)*new_r10);
17752 CheckValue<IkReal> x1405 = IKatan2WithCheck(IkReal((((gconst17*new_r11))+((gconst17*new_r00)))),IkReal(((((-1.0)*gconst17*x1404))+((gconst17*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
17753 if(!x1405.valid){
17754 continue;
17755 }
17756 CheckValue<IkReal> x1406=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*new_r01))+(((-1.0)*new_r11*x1404)))),-1);
17757 if(!x1406.valid){
17758 continue;
17759 }
17760 j3array[0]=((-1.5707963267949)+(x1405.value)+(((1.5707963267949)*(x1406.value))));
17761 sj3array[0]=IKsin(j3array[0]);
17762 cj3array[0]=IKcos(j3array[0]);
17763 if( j3array[0] > IKPI )
17764 {
17765  j3array[0]-=IK2PI;
17766 }
17767 else if( j3array[0] < -IKPI )
17768 { j3array[0]+=IK2PI;
17769 }
17770 j3valid[0] = true;
17771 for(int ij3 = 0; ij3 < 1; ++ij3)
17772 {
17773 if( !j3valid[ij3] )
17774 {
17775  continue;
17776 }
17777 _ij3[0] = ij3; _ij3[1] = -1;
17778 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17779 {
17780 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17781 {
17782  j3valid[iij3]=false; _ij3[1] = iij3; break;
17783 }
17784 }
17785 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17786 {
17787 IkReal evalcond[8];
17788 IkReal x1407=IKsin(j3);
17789 IkReal x1408=IKcos(j3);
17790 IkReal x1409=((1.0)*gconst16);
17791 IkReal x1410=(gconst17*x1407);
17792 IkReal x1411=(gconst17*x1408);
17793 IkReal x1412=((1.0)*x1408);
17794 IkReal x1413=(x1408*x1409);
17795 evalcond[0]=(gconst17+((new_r10*x1407))+((new_r00*x1408)));
17796 evalcond[1]=(((gconst16*x1407))+x1411+new_r00);
17797 evalcond[2]=((((-1.0)*new_r10*x1412))+gconst16+((new_r00*x1407)));
17798 evalcond[3]=((((-1.0)*new_r11*x1412))+((new_r01*x1407))+gconst17);
17799 evalcond[4]=((((-1.0)*x1413))+x1410+new_r01);
17800 evalcond[5]=((((-1.0)*x1413))+x1410+new_r10);
17801 evalcond[6]=(((new_r01*x1408))+((new_r11*x1407))+(((-1.0)*x1409)));
17802 evalcond[7]=((((-1.0)*x1407*x1409))+new_r11+(((-1.0)*x1411)));
17803 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17804 {
17805 continue;
17806 }
17807 }
17808 
17809 {
17810 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17811 vinfos[0].jointtype = 1;
17812 vinfos[0].foffset = j0;
17813 vinfos[0].indices[0] = _ij0[0];
17814 vinfos[0].indices[1] = _ij0[1];
17815 vinfos[0].maxsolutions = _nj0;
17816 vinfos[1].jointtype = 1;
17817 vinfos[1].foffset = j1;
17818 vinfos[1].indices[0] = _ij1[0];
17819 vinfos[1].indices[1] = _ij1[1];
17820 vinfos[1].maxsolutions = _nj1;
17821 vinfos[2].jointtype = 1;
17822 vinfos[2].foffset = j2;
17823 vinfos[2].indices[0] = _ij2[0];
17824 vinfos[2].indices[1] = _ij2[1];
17825 vinfos[2].maxsolutions = _nj2;
17826 vinfos[3].jointtype = 1;
17827 vinfos[3].foffset = j3;
17828 vinfos[3].indices[0] = _ij3[0];
17829 vinfos[3].indices[1] = _ij3[1];
17830 vinfos[3].maxsolutions = _nj3;
17831 vinfos[4].jointtype = 1;
17832 vinfos[4].foffset = j4;
17833 vinfos[4].indices[0] = _ij4[0];
17834 vinfos[4].indices[1] = _ij4[1];
17835 vinfos[4].maxsolutions = _nj4;
17836 vinfos[5].jointtype = 1;
17837 vinfos[5].foffset = j5;
17838 vinfos[5].indices[0] = _ij5[0];
17839 vinfos[5].indices[1] = _ij5[1];
17840 vinfos[5].maxsolutions = _nj5;
17841 std::vector<int> vfree(0);
17842 solutions.AddSolution(vinfos,vfree);
17843 }
17844 }
17845 }
17846 
17847 }
17848 
17849 }
17850 
17851 }
17852 } while(0);
17853 if( bgotonextstatement )
17854 {
17855 bool bgotonextstatement = true;
17856 do
17857 {
17858 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j5)))), 6.28318530717959)));
17859 if( IKabs(evalcond[0]) < 0.0000050000000000 )
17860 {
17861 bgotonextstatement=false;
17862 {
17863 IkReal j3array[1], cj3array[1], sj3array[1];
17864 bool j3valid[1]={false};
17865 _nj3 = 1;
17866 if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(new_r01)-1) <= IKFAST_SINCOS_THRESH )
17867  continue;
17868 j3array[0]=IKatan2(((-1.0)*new_r00), new_r01);
17869 sj3array[0]=IKsin(j3array[0]);
17870 cj3array[0]=IKcos(j3array[0]);
17871 if( j3array[0] > IKPI )
17872 {
17873  j3array[0]-=IK2PI;
17874 }
17875 else if( j3array[0] < -IKPI )
17876 { j3array[0]+=IK2PI;
17877 }
17878 j3valid[0] = true;
17879 for(int ij3 = 0; ij3 < 1; ++ij3)
17880 {
17881 if( !j3valid[ij3] )
17882 {
17883  continue;
17884 }
17885 _ij3[0] = ij3; _ij3[1] = -1;
17886 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17887 {
17888 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17889 {
17890  j3valid[iij3]=false; _ij3[1] = iij3; break;
17891 }
17892 }
17893 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17894 {
17895 IkReal evalcond[8];
17896 IkReal x1414=IKsin(j3);
17897 IkReal x1415=IKcos(j3);
17898 IkReal x1416=((1.0)*x1415);
17899 evalcond[0]=(x1414+new_r00);
17900 evalcond[1]=((((-1.0)*x1416))+new_r01);
17901 evalcond[2]=(new_r11+(((-1.0)*x1414)));
17902 evalcond[3]=((((-1.0)*x1416))+new_r10);
17903 evalcond[4]=(((new_r00*x1415))+((new_r10*x1414)));
17904 evalcond[5]=((((-1.0)*new_r11*x1416))+((new_r01*x1414)));
17905 evalcond[6]=((-1.0)+((new_r01*x1415))+((new_r11*x1414)));
17906 evalcond[7]=((1.0)+(((-1.0)*new_r10*x1416))+((new_r00*x1414)));
17907 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
17908 {
17909 continue;
17910 }
17911 }
17912 
17913 {
17914 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17915 vinfos[0].jointtype = 1;
17916 vinfos[0].foffset = j0;
17917 vinfos[0].indices[0] = _ij0[0];
17918 vinfos[0].indices[1] = _ij0[1];
17919 vinfos[0].maxsolutions = _nj0;
17920 vinfos[1].jointtype = 1;
17921 vinfos[1].foffset = j1;
17922 vinfos[1].indices[0] = _ij1[0];
17923 vinfos[1].indices[1] = _ij1[1];
17924 vinfos[1].maxsolutions = _nj1;
17925 vinfos[2].jointtype = 1;
17926 vinfos[2].foffset = j2;
17927 vinfos[2].indices[0] = _ij2[0];
17928 vinfos[2].indices[1] = _ij2[1];
17929 vinfos[2].maxsolutions = _nj2;
17930 vinfos[3].jointtype = 1;
17931 vinfos[3].foffset = j3;
17932 vinfos[3].indices[0] = _ij3[0];
17933 vinfos[3].indices[1] = _ij3[1];
17934 vinfos[3].maxsolutions = _nj3;
17935 vinfos[4].jointtype = 1;
17936 vinfos[4].foffset = j4;
17937 vinfos[4].indices[0] = _ij4[0];
17938 vinfos[4].indices[1] = _ij4[1];
17939 vinfos[4].maxsolutions = _nj4;
17940 vinfos[5].jointtype = 1;
17941 vinfos[5].foffset = j5;
17942 vinfos[5].indices[0] = _ij5[0];
17943 vinfos[5].indices[1] = _ij5[1];
17944 vinfos[5].maxsolutions = _nj5;
17945 std::vector<int> vfree(0);
17946 solutions.AddSolution(vinfos,vfree);
17947 }
17948 }
17949 }
17950 
17951 }
17952 } while(0);
17953 if( bgotonextstatement )
17954 {
17955 bool bgotonextstatement = true;
17956 do
17957 {
17958 evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j5)))), 6.28318530717959)));
17959 if( IKabs(evalcond[0]) < 0.0000050000000000 )
17960 {
17961 bgotonextstatement=false;
17962 {
17963 IkReal j3array[1], cj3array[1], sj3array[1];
17964 bool j3valid[1]={false};
17965 _nj3 = 1;
17966 if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(((-1.0)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
17967  continue;
17968 j3array[0]=IKatan2(((-1.0)*new_r11), ((-1.0)*new_r01));
17969 sj3array[0]=IKsin(j3array[0]);
17970 cj3array[0]=IKcos(j3array[0]);
17971 if( j3array[0] > IKPI )
17972 {
17973  j3array[0]-=IK2PI;
17974 }
17975 else if( j3array[0] < -IKPI )
17976 { j3array[0]+=IK2PI;
17977 }
17978 j3valid[0] = true;
17979 for(int ij3 = 0; ij3 < 1; ++ij3)
17980 {
17981 if( !j3valid[ij3] )
17982 {
17983  continue;
17984 }
17985 _ij3[0] = ij3; _ij3[1] = -1;
17986 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17987 {
17988 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17989 {
17990  j3valid[iij3]=false; _ij3[1] = iij3; break;
17991 }
17992 }
17993 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17994 {
17995 IkReal evalcond[8];
17996 IkReal x1417=IKcos(j3);
17997 IkReal x1418=IKsin(j3);
17998 IkReal x1419=((1.0)*x1417);
17999 evalcond[0]=(x1417+new_r01);
18000 evalcond[1]=(x1418+new_r11);
18001 evalcond[2]=(x1417+new_r10);
18002 evalcond[3]=(new_r00+(((-1.0)*x1418)));
18003 evalcond[4]=(((new_r00*x1417))+((new_r10*x1418)));
18004 evalcond[5]=((((-1.0)*new_r11*x1419))+((new_r01*x1418)));
18005 evalcond[6]=((1.0)+((new_r01*x1417))+((new_r11*x1418)));
18006 evalcond[7]=((-1.0)+(((-1.0)*new_r10*x1419))+((new_r00*x1418)));
18007 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
18008 {
18009 continue;
18010 }
18011 }
18012 
18013 {
18014 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18015 vinfos[0].jointtype = 1;
18016 vinfos[0].foffset = j0;
18017 vinfos[0].indices[0] = _ij0[0];
18018 vinfos[0].indices[1] = _ij0[1];
18019 vinfos[0].maxsolutions = _nj0;
18020 vinfos[1].jointtype = 1;
18021 vinfos[1].foffset = j1;
18022 vinfos[1].indices[0] = _ij1[0];
18023 vinfos[1].indices[1] = _ij1[1];
18024 vinfos[1].maxsolutions = _nj1;
18025 vinfos[2].jointtype = 1;
18026 vinfos[2].foffset = j2;
18027 vinfos[2].indices[0] = _ij2[0];
18028 vinfos[2].indices[1] = _ij2[1];
18029 vinfos[2].maxsolutions = _nj2;
18030 vinfos[3].jointtype = 1;
18031 vinfos[3].foffset = j3;
18032 vinfos[3].indices[0] = _ij3[0];
18033 vinfos[3].indices[1] = _ij3[1];
18034 vinfos[3].maxsolutions = _nj3;
18035 vinfos[4].jointtype = 1;
18036 vinfos[4].foffset = j4;
18037 vinfos[4].indices[0] = _ij4[0];
18038 vinfos[4].indices[1] = _ij4[1];
18039 vinfos[4].maxsolutions = _nj4;
18040 vinfos[5].jointtype = 1;
18041 vinfos[5].foffset = j5;
18042 vinfos[5].indices[0] = _ij5[0];
18043 vinfos[5].indices[1] = _ij5[1];
18044 vinfos[5].maxsolutions = _nj5;
18045 std::vector<int> vfree(0);
18046 solutions.AddSolution(vinfos,vfree);
18047 }
18048 }
18049 }
18050 
18051 }
18052 } while(0);
18053 if( bgotonextstatement )
18054 {
18055 bool bgotonextstatement = true;
18056 do
18057 {
18058 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
18059 if( IKabs(evalcond[0]) < 0.0000050000000000 )
18060 {
18061 bgotonextstatement=false;
18062 {
18063 IkReal j3eval[3];
18064 sj4=0;
18065 cj4=-1.0;
18066 j4=3.14159265358979;
18067 new_r11=0;
18068 new_r00=0;
18069 j3eval[0]=new_r10;
18070 j3eval[1]=IKsign(new_r10);
18071 j3eval[2]=((IKabs(cj5))+(IKabs(sj5)));
18072 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
18073 {
18074 {
18075 IkReal j3eval[3];
18076 sj4=0;
18077 cj4=-1.0;
18078 j4=3.14159265358979;
18079 new_r11=0;
18080 new_r00=0;
18081 j3eval[0]=new_r01;
18082 j3eval[1]=IKsign(new_r01);
18083 j3eval[2]=((IKabs(cj5))+(IKabs(sj5)));
18084 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
18085 {
18086 {
18087 IkReal j3eval[2];
18088 sj4=0;
18089 cj4=-1.0;
18090 j4=3.14159265358979;
18091 new_r11=0;
18092 new_r00=0;
18093 j3eval[0]=new_r01;
18094 j3eval[1]=new_r10;
18095 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
18096 {
18097 continue; // no branches [j3]
18098 
18099 } else
18100 {
18101 {
18102 IkReal j3array[1], cj3array[1], sj3array[1];
18103 bool j3valid[1]={false};
18104 _nj3 = 1;
18105 CheckValue<IkReal> x1420=IKPowWithIntegerCheck(new_r01,-1);
18106 if(!x1420.valid){
18107 continue;
18108 }
18109 CheckValue<IkReal> x1421=IKPowWithIntegerCheck(new_r10,-1);
18110 if(!x1421.valid){
18111 continue;
18112 }
18113 if( IKabs(((-1.0)*cj5*(x1420.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((sj5*(x1421.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*cj5*(x1420.value)))+IKsqr((sj5*(x1421.value)))-1) <= IKFAST_SINCOS_THRESH )
18114  continue;
18115 j3array[0]=IKatan2(((-1.0)*cj5*(x1420.value)), (sj5*(x1421.value)));
18116 sj3array[0]=IKsin(j3array[0]);
18117 cj3array[0]=IKcos(j3array[0]);
18118 if( j3array[0] > IKPI )
18119 {
18120  j3array[0]-=IK2PI;
18121 }
18122 else if( j3array[0] < -IKPI )
18123 { j3array[0]+=IK2PI;
18124 }
18125 j3valid[0] = true;
18126 for(int ij3 = 0; ij3 < 1; ++ij3)
18127 {
18128 if( !j3valid[ij3] )
18129 {
18130  continue;
18131 }
18132 _ij3[0] = ij3; _ij3[1] = -1;
18133 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18134 {
18135 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18136 {
18137  j3valid[iij3]=false; _ij3[1] = iij3; break;
18138 }
18139 }
18140 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18141 {
18142 IkReal evalcond[7];
18143 IkReal x1422=IKsin(j3);
18144 IkReal x1423=IKcos(j3);
18145 IkReal x1424=((1.0)*sj5);
18146 IkReal x1425=(cj5*x1422);
18147 IkReal x1426=(x1423*x1424);
18148 evalcond[0]=(cj5+((new_r01*x1422)));
18149 evalcond[1]=(cj5+((new_r10*x1422)));
18150 evalcond[2]=(sj5+(((-1.0)*new_r10*x1423)));
18151 evalcond[3]=(((new_r01*x1423))+(((-1.0)*x1424)));
18152 evalcond[4]=(((sj5*x1422))+((cj5*x1423)));
18153 evalcond[5]=(x1425+new_r01+(((-1.0)*x1426)));
18154 evalcond[6]=(x1425+new_r10+(((-1.0)*x1426)));
18155 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18156 {
18157 continue;
18158 }
18159 }
18160 
18161 {
18162 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18163 vinfos[0].jointtype = 1;
18164 vinfos[0].foffset = j0;
18165 vinfos[0].indices[0] = _ij0[0];
18166 vinfos[0].indices[1] = _ij0[1];
18167 vinfos[0].maxsolutions = _nj0;
18168 vinfos[1].jointtype = 1;
18169 vinfos[1].foffset = j1;
18170 vinfos[1].indices[0] = _ij1[0];
18171 vinfos[1].indices[1] = _ij1[1];
18172 vinfos[1].maxsolutions = _nj1;
18173 vinfos[2].jointtype = 1;
18174 vinfos[2].foffset = j2;
18175 vinfos[2].indices[0] = _ij2[0];
18176 vinfos[2].indices[1] = _ij2[1];
18177 vinfos[2].maxsolutions = _nj2;
18178 vinfos[3].jointtype = 1;
18179 vinfos[3].foffset = j3;
18180 vinfos[3].indices[0] = _ij3[0];
18181 vinfos[3].indices[1] = _ij3[1];
18182 vinfos[3].maxsolutions = _nj3;
18183 vinfos[4].jointtype = 1;
18184 vinfos[4].foffset = j4;
18185 vinfos[4].indices[0] = _ij4[0];
18186 vinfos[4].indices[1] = _ij4[1];
18187 vinfos[4].maxsolutions = _nj4;
18188 vinfos[5].jointtype = 1;
18189 vinfos[5].foffset = j5;
18190 vinfos[5].indices[0] = _ij5[0];
18191 vinfos[5].indices[1] = _ij5[1];
18192 vinfos[5].maxsolutions = _nj5;
18193 std::vector<int> vfree(0);
18194 solutions.AddSolution(vinfos,vfree);
18195 }
18196 }
18197 }
18198 
18199 }
18200 
18201 }
18202 
18203 } else
18204 {
18205 {
18206 IkReal j3array[1], cj3array[1], sj3array[1];
18207 bool j3valid[1]={false};
18208 _nj3 = 1;
18210 if(!x1427.valid){
18211 continue;
18212 }
18213 CheckValue<IkReal> x1428 = IKatan2WithCheck(IkReal(((-1.0)*cj5)),IkReal(sj5),IKFAST_ATAN2_MAGTHRESH);
18214 if(!x1428.valid){
18215 continue;
18216 }
18217 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1427.value)))+(x1428.value));
18218 sj3array[0]=IKsin(j3array[0]);
18219 cj3array[0]=IKcos(j3array[0]);
18220 if( j3array[0] > IKPI )
18221 {
18222  j3array[0]-=IK2PI;
18223 }
18224 else if( j3array[0] < -IKPI )
18225 { j3array[0]+=IK2PI;
18226 }
18227 j3valid[0] = true;
18228 for(int ij3 = 0; ij3 < 1; ++ij3)
18229 {
18230 if( !j3valid[ij3] )
18231 {
18232  continue;
18233 }
18234 _ij3[0] = ij3; _ij3[1] = -1;
18235 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18236 {
18237 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18238 {
18239  j3valid[iij3]=false; _ij3[1] = iij3; break;
18240 }
18241 }
18242 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18243 {
18244 IkReal evalcond[7];
18245 IkReal x1429=IKsin(j3);
18246 IkReal x1430=IKcos(j3);
18247 IkReal x1431=((1.0)*sj5);
18248 IkReal x1432=(cj5*x1429);
18249 IkReal x1433=(x1430*x1431);
18250 evalcond[0]=(cj5+((new_r01*x1429)));
18251 evalcond[1]=(cj5+((new_r10*x1429)));
18252 evalcond[2]=(sj5+(((-1.0)*new_r10*x1430)));
18253 evalcond[3]=(((new_r01*x1430))+(((-1.0)*x1431)));
18254 evalcond[4]=(((cj5*x1430))+((sj5*x1429)));
18255 evalcond[5]=((((-1.0)*x1433))+x1432+new_r01);
18256 evalcond[6]=((((-1.0)*x1433))+x1432+new_r10);
18257 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18258 {
18259 continue;
18260 }
18261 }
18262 
18263 {
18264 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18265 vinfos[0].jointtype = 1;
18266 vinfos[0].foffset = j0;
18267 vinfos[0].indices[0] = _ij0[0];
18268 vinfos[0].indices[1] = _ij0[1];
18269 vinfos[0].maxsolutions = _nj0;
18270 vinfos[1].jointtype = 1;
18271 vinfos[1].foffset = j1;
18272 vinfos[1].indices[0] = _ij1[0];
18273 vinfos[1].indices[1] = _ij1[1];
18274 vinfos[1].maxsolutions = _nj1;
18275 vinfos[2].jointtype = 1;
18276 vinfos[2].foffset = j2;
18277 vinfos[2].indices[0] = _ij2[0];
18278 vinfos[2].indices[1] = _ij2[1];
18279 vinfos[2].maxsolutions = _nj2;
18280 vinfos[3].jointtype = 1;
18281 vinfos[3].foffset = j3;
18282 vinfos[3].indices[0] = _ij3[0];
18283 vinfos[3].indices[1] = _ij3[1];
18284 vinfos[3].maxsolutions = _nj3;
18285 vinfos[4].jointtype = 1;
18286 vinfos[4].foffset = j4;
18287 vinfos[4].indices[0] = _ij4[0];
18288 vinfos[4].indices[1] = _ij4[1];
18289 vinfos[4].maxsolutions = _nj4;
18290 vinfos[5].jointtype = 1;
18291 vinfos[5].foffset = j5;
18292 vinfos[5].indices[0] = _ij5[0];
18293 vinfos[5].indices[1] = _ij5[1];
18294 vinfos[5].maxsolutions = _nj5;
18295 std::vector<int> vfree(0);
18296 solutions.AddSolution(vinfos,vfree);
18297 }
18298 }
18299 }
18300 
18301 }
18302 
18303 }
18304 
18305 } else
18306 {
18307 {
18308 IkReal j3array[1], cj3array[1], sj3array[1];
18309 bool j3valid[1]={false};
18310 _nj3 = 1;
18312 if(!x1434.valid){
18313 continue;
18314 }
18315 CheckValue<IkReal> x1435 = IKatan2WithCheck(IkReal(((-1.0)*cj5)),IkReal(sj5),IKFAST_ATAN2_MAGTHRESH);
18316 if(!x1435.valid){
18317 continue;
18318 }
18319 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1434.value)))+(x1435.value));
18320 sj3array[0]=IKsin(j3array[0]);
18321 cj3array[0]=IKcos(j3array[0]);
18322 if( j3array[0] > IKPI )
18323 {
18324  j3array[0]-=IK2PI;
18325 }
18326 else if( j3array[0] < -IKPI )
18327 { j3array[0]+=IK2PI;
18328 }
18329 j3valid[0] = true;
18330 for(int ij3 = 0; ij3 < 1; ++ij3)
18331 {
18332 if( !j3valid[ij3] )
18333 {
18334  continue;
18335 }
18336 _ij3[0] = ij3; _ij3[1] = -1;
18337 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18338 {
18339 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18340 {
18341  j3valid[iij3]=false; _ij3[1] = iij3; break;
18342 }
18343 }
18344 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18345 {
18346 IkReal evalcond[7];
18347 IkReal x1436=IKsin(j3);
18348 IkReal x1437=IKcos(j3);
18349 IkReal x1438=((1.0)*sj5);
18350 IkReal x1439=(cj5*x1436);
18351 IkReal x1440=(x1437*x1438);
18352 evalcond[0]=(cj5+((new_r01*x1436)));
18353 evalcond[1]=(cj5+((new_r10*x1436)));
18354 evalcond[2]=(sj5+(((-1.0)*new_r10*x1437)));
18355 evalcond[3]=(((new_r01*x1437))+(((-1.0)*x1438)));
18356 evalcond[4]=(((sj5*x1436))+((cj5*x1437)));
18357 evalcond[5]=(x1439+(((-1.0)*x1440))+new_r01);
18358 evalcond[6]=(x1439+(((-1.0)*x1440))+new_r10);
18359 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18360 {
18361 continue;
18362 }
18363 }
18364 
18365 {
18366 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18367 vinfos[0].jointtype = 1;
18368 vinfos[0].foffset = j0;
18369 vinfos[0].indices[0] = _ij0[0];
18370 vinfos[0].indices[1] = _ij0[1];
18371 vinfos[0].maxsolutions = _nj0;
18372 vinfos[1].jointtype = 1;
18373 vinfos[1].foffset = j1;
18374 vinfos[1].indices[0] = _ij1[0];
18375 vinfos[1].indices[1] = _ij1[1];
18376 vinfos[1].maxsolutions = _nj1;
18377 vinfos[2].jointtype = 1;
18378 vinfos[2].foffset = j2;
18379 vinfos[2].indices[0] = _ij2[0];
18380 vinfos[2].indices[1] = _ij2[1];
18381 vinfos[2].maxsolutions = _nj2;
18382 vinfos[3].jointtype = 1;
18383 vinfos[3].foffset = j3;
18384 vinfos[3].indices[0] = _ij3[0];
18385 vinfos[3].indices[1] = _ij3[1];
18386 vinfos[3].maxsolutions = _nj3;
18387 vinfos[4].jointtype = 1;
18388 vinfos[4].foffset = j4;
18389 vinfos[4].indices[0] = _ij4[0];
18390 vinfos[4].indices[1] = _ij4[1];
18391 vinfos[4].maxsolutions = _nj4;
18392 vinfos[5].jointtype = 1;
18393 vinfos[5].foffset = j5;
18394 vinfos[5].indices[0] = _ij5[0];
18395 vinfos[5].indices[1] = _ij5[1];
18396 vinfos[5].maxsolutions = _nj5;
18397 std::vector<int> vfree(0);
18398 solutions.AddSolution(vinfos,vfree);
18399 }
18400 }
18401 }
18402 
18403 }
18404 
18405 }
18406 
18407 }
18408 } while(0);
18409 if( bgotonextstatement )
18410 {
18411 bool bgotonextstatement = true;
18412 do
18413 {
18414 evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
18415 if( IKabs(evalcond[0]) < 0.0000050000000000 )
18416 {
18417 bgotonextstatement=false;
18418 {
18419 IkReal j3eval[1];
18420 sj4=0;
18421 cj4=-1.0;
18422 j4=3.14159265358979;
18423 new_r11=0;
18424 new_r01=0;
18425 new_r22=0;
18426 new_r20=0;
18427 j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
18428 if( IKabs(j3eval[0]) < 0.0000010000000000 )
18429 {
18430 continue; // no branches [j3]
18431 
18432 } else
18433 {
18434 {
18435 IkReal j3array[2], cj3array[2], sj3array[2];
18436 bool j3valid[2]={false};
18437 _nj3 = 2;
18438 CheckValue<IkReal> x1442 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
18439 if(!x1442.valid){
18440 continue;
18441 }
18442 IkReal x1441=x1442.value;
18443 j3array[0]=((-1.0)*x1441);
18444 sj3array[0]=IKsin(j3array[0]);
18445 cj3array[0]=IKcos(j3array[0]);
18446 j3array[1]=((3.14159265358979)+(((-1.0)*x1441)));
18447 sj3array[1]=IKsin(j3array[1]);
18448 cj3array[1]=IKcos(j3array[1]);
18449 if( j3array[0] > IKPI )
18450 {
18451  j3array[0]-=IK2PI;
18452 }
18453 else if( j3array[0] < -IKPI )
18454 { j3array[0]+=IK2PI;
18455 }
18456 j3valid[0] = true;
18457 if( j3array[1] > IKPI )
18458 {
18459  j3array[1]-=IK2PI;
18460 }
18461 else if( j3array[1] < -IKPI )
18462 { j3array[1]+=IK2PI;
18463 }
18464 j3valid[1] = true;
18465 for(int ij3 = 0; ij3 < 2; ++ij3)
18466 {
18467 if( !j3valid[ij3] )
18468 {
18469  continue;
18470 }
18471 _ij3[0] = ij3; _ij3[1] = -1;
18472 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
18473 {
18474 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18475 {
18476  j3valid[iij3]=false; _ij3[1] = iij3; break;
18477 }
18478 }
18479 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18480 {
18481 IkReal evalcond[1];
18482 evalcond[0]=(((new_r00*(IKsin(j3))))+(((-1.0)*new_r10*(IKcos(j3)))));
18483 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
18484 {
18485 continue;
18486 }
18487 }
18488 
18489 {
18490 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18491 vinfos[0].jointtype = 1;
18492 vinfos[0].foffset = j0;
18493 vinfos[0].indices[0] = _ij0[0];
18494 vinfos[0].indices[1] = _ij0[1];
18495 vinfos[0].maxsolutions = _nj0;
18496 vinfos[1].jointtype = 1;
18497 vinfos[1].foffset = j1;
18498 vinfos[1].indices[0] = _ij1[0];
18499 vinfos[1].indices[1] = _ij1[1];
18500 vinfos[1].maxsolutions = _nj1;
18501 vinfos[2].jointtype = 1;
18502 vinfos[2].foffset = j2;
18503 vinfos[2].indices[0] = _ij2[0];
18504 vinfos[2].indices[1] = _ij2[1];
18505 vinfos[2].maxsolutions = _nj2;
18506 vinfos[3].jointtype = 1;
18507 vinfos[3].foffset = j3;
18508 vinfos[3].indices[0] = _ij3[0];
18509 vinfos[3].indices[1] = _ij3[1];
18510 vinfos[3].maxsolutions = _nj3;
18511 vinfos[4].jointtype = 1;
18512 vinfos[4].foffset = j4;
18513 vinfos[4].indices[0] = _ij4[0];
18514 vinfos[4].indices[1] = _ij4[1];
18515 vinfos[4].maxsolutions = _nj4;
18516 vinfos[5].jointtype = 1;
18517 vinfos[5].foffset = j5;
18518 vinfos[5].indices[0] = _ij5[0];
18519 vinfos[5].indices[1] = _ij5[1];
18520 vinfos[5].maxsolutions = _nj5;
18521 std::vector<int> vfree(0);
18522 solutions.AddSolution(vinfos,vfree);
18523 }
18524 }
18525 }
18526 
18527 }
18528 
18529 }
18530 
18531 }
18532 } while(0);
18533 if( bgotonextstatement )
18534 {
18535 bool bgotonextstatement = true;
18536 do
18537 {
18538 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
18539 if( IKabs(evalcond[0]) < 0.0000050000000000 )
18540 {
18541 bgotonextstatement=false;
18542 {
18543 IkReal j3eval[1];
18544 sj4=0;
18545 cj4=-1.0;
18546 j4=3.14159265358979;
18547 new_r00=0;
18548 new_r10=0;
18549 new_r21=0;
18550 new_r22=0;
18551 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
18552 if( IKabs(j3eval[0]) < 0.0000010000000000 )
18553 {
18554 continue; // no branches [j3]
18555 
18556 } else
18557 {
18558 {
18559 IkReal j3array[2], cj3array[2], sj3array[2];
18560 bool j3valid[2]={false};
18561 _nj3 = 2;
18562 CheckValue<IkReal> x1444 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
18563 if(!x1444.valid){
18564 continue;
18565 }
18566 IkReal x1443=x1444.value;
18567 j3array[0]=((-1.0)*x1443);
18568 sj3array[0]=IKsin(j3array[0]);
18569 cj3array[0]=IKcos(j3array[0]);
18570 j3array[1]=((3.14159265358979)+(((-1.0)*x1443)));
18571 sj3array[1]=IKsin(j3array[1]);
18572 cj3array[1]=IKcos(j3array[1]);
18573 if( j3array[0] > IKPI )
18574 {
18575  j3array[0]-=IK2PI;
18576 }
18577 else if( j3array[0] < -IKPI )
18578 { j3array[0]+=IK2PI;
18579 }
18580 j3valid[0] = true;
18581 if( j3array[1] > IKPI )
18582 {
18583  j3array[1]-=IK2PI;
18584 }
18585 else if( j3array[1] < -IKPI )
18586 { j3array[1]+=IK2PI;
18587 }
18588 j3valid[1] = true;
18589 for(int ij3 = 0; ij3 < 2; ++ij3)
18590 {
18591 if( !j3valid[ij3] )
18592 {
18593  continue;
18594 }
18595 _ij3[0] = ij3; _ij3[1] = -1;
18596 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
18597 {
18598 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18599 {
18600  j3valid[iij3]=false; _ij3[1] = iij3; break;
18601 }
18602 }
18603 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18604 {
18605 IkReal evalcond[1];
18606 evalcond[0]=(((new_r01*(IKsin(j3))))+(((-1.0)*new_r11*(IKcos(j3)))));
18607 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
18608 {
18609 continue;
18610 }
18611 }
18612 
18613 {
18614 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18615 vinfos[0].jointtype = 1;
18616 vinfos[0].foffset = j0;
18617 vinfos[0].indices[0] = _ij0[0];
18618 vinfos[0].indices[1] = _ij0[1];
18619 vinfos[0].maxsolutions = _nj0;
18620 vinfos[1].jointtype = 1;
18621 vinfos[1].foffset = j1;
18622 vinfos[1].indices[0] = _ij1[0];
18623 vinfos[1].indices[1] = _ij1[1];
18624 vinfos[1].maxsolutions = _nj1;
18625 vinfos[2].jointtype = 1;
18626 vinfos[2].foffset = j2;
18627 vinfos[2].indices[0] = _ij2[0];
18628 vinfos[2].indices[1] = _ij2[1];
18629 vinfos[2].maxsolutions = _nj2;
18630 vinfos[3].jointtype = 1;
18631 vinfos[3].foffset = j3;
18632 vinfos[3].indices[0] = _ij3[0];
18633 vinfos[3].indices[1] = _ij3[1];
18634 vinfos[3].maxsolutions = _nj3;
18635 vinfos[4].jointtype = 1;
18636 vinfos[4].foffset = j4;
18637 vinfos[4].indices[0] = _ij4[0];
18638 vinfos[4].indices[1] = _ij4[1];
18639 vinfos[4].maxsolutions = _nj4;
18640 vinfos[5].jointtype = 1;
18641 vinfos[5].foffset = j5;
18642 vinfos[5].indices[0] = _ij5[0];
18643 vinfos[5].indices[1] = _ij5[1];
18644 vinfos[5].maxsolutions = _nj5;
18645 std::vector<int> vfree(0);
18646 solutions.AddSolution(vinfos,vfree);
18647 }
18648 }
18649 }
18650 
18651 }
18652 
18653 }
18654 
18655 }
18656 } while(0);
18657 if( bgotonextstatement )
18658 {
18659 bool bgotonextstatement = true;
18660 do
18661 {
18662 evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
18663 if( IKabs(evalcond[0]) < 0.0000050000000000 )
18664 {
18665 bgotonextstatement=false;
18666 {
18667 IkReal j3eval[3];
18668 sj4=0;
18669 cj4=-1.0;
18670 j4=3.14159265358979;
18671 new_r01=0;
18672 new_r10=0;
18673 j3eval[0]=new_r00;
18674 j3eval[1]=IKsign(new_r00);
18675 j3eval[2]=((IKabs(cj5))+(IKabs(sj5)));
18676 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
18677 {
18678 {
18679 IkReal j3eval[2];
18680 sj4=0;
18681 cj4=-1.0;
18682 j4=3.14159265358979;
18683 new_r01=0;
18684 new_r10=0;
18685 j3eval[0]=new_r00;
18686 j3eval[1]=new_r11;
18687 if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 )
18688 {
18689 continue; // no branches [j3]
18690 
18691 } else
18692 {
18693 {
18694 IkReal j3array[1], cj3array[1], sj3array[1];
18695 bool j3valid[1]={false};
18696 _nj3 = 1;
18697 CheckValue<IkReal> x1445=IKPowWithIntegerCheck(new_r00,-1);
18698 if(!x1445.valid){
18699 continue;
18700 }
18701 CheckValue<IkReal> x1446=IKPowWithIntegerCheck(new_r11,-1);
18702 if(!x1446.valid){
18703 continue;
18704 }
18705 if( IKabs(((-1.0)*sj5*(x1445.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((cj5*(x1446.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*sj5*(x1445.value)))+IKsqr((cj5*(x1446.value)))-1) <= IKFAST_SINCOS_THRESH )
18706  continue;
18707 j3array[0]=IKatan2(((-1.0)*sj5*(x1445.value)), (cj5*(x1446.value)));
18708 sj3array[0]=IKsin(j3array[0]);
18709 cj3array[0]=IKcos(j3array[0]);
18710 if( j3array[0] > IKPI )
18711 {
18712  j3array[0]-=IK2PI;
18713 }
18714 else if( j3array[0] < -IKPI )
18715 { j3array[0]+=IK2PI;
18716 }
18717 j3valid[0] = true;
18718 for(int ij3 = 0; ij3 < 1; ++ij3)
18719 {
18720 if( !j3valid[ij3] )
18721 {
18722  continue;
18723 }
18724 _ij3[0] = ij3; _ij3[1] = -1;
18725 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18726 {
18727 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18728 {
18729  j3valid[iij3]=false; _ij3[1] = iij3; break;
18730 }
18731 }
18732 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18733 {
18734 IkReal evalcond[7];
18735 IkReal x1447=IKcos(j3);
18736 IkReal x1448=IKsin(j3);
18737 IkReal x1449=((1.0)*sj5);
18738 IkReal x1450=(cj5*x1447);
18739 IkReal x1451=((1.0)*x1447);
18740 evalcond[0]=(sj5+((new_r00*x1448)));
18741 evalcond[1]=(cj5+((new_r00*x1447)));
18742 evalcond[2]=(cj5+(((-1.0)*new_r11*x1451)));
18743 evalcond[3]=(((new_r11*x1448))+(((-1.0)*x1449)));
18744 evalcond[4]=((((-1.0)*x1447*x1449))+((cj5*x1448)));
18745 evalcond[5]=(((sj5*x1448))+x1450+new_r00);
18746 evalcond[6]=((((-1.0)*x1450))+new_r11+(((-1.0)*x1448*x1449)));
18747 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18748 {
18749 continue;
18750 }
18751 }
18752 
18753 {
18754 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18755 vinfos[0].jointtype = 1;
18756 vinfos[0].foffset = j0;
18757 vinfos[0].indices[0] = _ij0[0];
18758 vinfos[0].indices[1] = _ij0[1];
18759 vinfos[0].maxsolutions = _nj0;
18760 vinfos[1].jointtype = 1;
18761 vinfos[1].foffset = j1;
18762 vinfos[1].indices[0] = _ij1[0];
18763 vinfos[1].indices[1] = _ij1[1];
18764 vinfos[1].maxsolutions = _nj1;
18765 vinfos[2].jointtype = 1;
18766 vinfos[2].foffset = j2;
18767 vinfos[2].indices[0] = _ij2[0];
18768 vinfos[2].indices[1] = _ij2[1];
18769 vinfos[2].maxsolutions = _nj2;
18770 vinfos[3].jointtype = 1;
18771 vinfos[3].foffset = j3;
18772 vinfos[3].indices[0] = _ij3[0];
18773 vinfos[3].indices[1] = _ij3[1];
18774 vinfos[3].maxsolutions = _nj3;
18775 vinfos[4].jointtype = 1;
18776 vinfos[4].foffset = j4;
18777 vinfos[4].indices[0] = _ij4[0];
18778 vinfos[4].indices[1] = _ij4[1];
18779 vinfos[4].maxsolutions = _nj4;
18780 vinfos[5].jointtype = 1;
18781 vinfos[5].foffset = j5;
18782 vinfos[5].indices[0] = _ij5[0];
18783 vinfos[5].indices[1] = _ij5[1];
18784 vinfos[5].maxsolutions = _nj5;
18785 std::vector<int> vfree(0);
18786 solutions.AddSolution(vinfos,vfree);
18787 }
18788 }
18789 }
18790 
18791 }
18792 
18793 }
18794 
18795 } else
18796 {
18797 {
18798 IkReal j3array[1], cj3array[1], sj3array[1];
18799 bool j3valid[1]={false};
18800 _nj3 = 1;
18801 CheckValue<IkReal> x1452 = IKatan2WithCheck(IkReal(((-1.0)*sj5)),IkReal(((-1.0)*cj5)),IKFAST_ATAN2_MAGTHRESH);
18802 if(!x1452.valid){
18803 continue;
18804 }
18806 if(!x1453.valid){
18807 continue;
18808 }
18809 j3array[0]=((-1.5707963267949)+(x1452.value)+(((1.5707963267949)*(x1453.value))));
18810 sj3array[0]=IKsin(j3array[0]);
18811 cj3array[0]=IKcos(j3array[0]);
18812 if( j3array[0] > IKPI )
18813 {
18814  j3array[0]-=IK2PI;
18815 }
18816 else if( j3array[0] < -IKPI )
18817 { j3array[0]+=IK2PI;
18818 }
18819 j3valid[0] = true;
18820 for(int ij3 = 0; ij3 < 1; ++ij3)
18821 {
18822 if( !j3valid[ij3] )
18823 {
18824  continue;
18825 }
18826 _ij3[0] = ij3; _ij3[1] = -1;
18827 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18828 {
18829 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18830 {
18831  j3valid[iij3]=false; _ij3[1] = iij3; break;
18832 }
18833 }
18834 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18835 {
18836 IkReal evalcond[7];
18837 IkReal x1454=IKcos(j3);
18838 IkReal x1455=IKsin(j3);
18839 IkReal x1456=((1.0)*sj5);
18840 IkReal x1457=(cj5*x1454);
18841 IkReal x1458=((1.0)*x1454);
18842 evalcond[0]=(sj5+((new_r00*x1455)));
18843 evalcond[1]=(cj5+((new_r00*x1454)));
18844 evalcond[2]=(cj5+(((-1.0)*new_r11*x1458)));
18845 evalcond[3]=((((-1.0)*x1456))+((new_r11*x1455)));
18846 evalcond[4]=(((cj5*x1455))+(((-1.0)*x1454*x1456)));
18847 evalcond[5]=(((sj5*x1455))+x1457+new_r00);
18848 evalcond[6]=((((-1.0)*x1457))+(((-1.0)*x1455*x1456))+new_r11);
18849 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18850 {
18851 continue;
18852 }
18853 }
18854 
18855 {
18856 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18857 vinfos[0].jointtype = 1;
18858 vinfos[0].foffset = j0;
18859 vinfos[0].indices[0] = _ij0[0];
18860 vinfos[0].indices[1] = _ij0[1];
18861 vinfos[0].maxsolutions = _nj0;
18862 vinfos[1].jointtype = 1;
18863 vinfos[1].foffset = j1;
18864 vinfos[1].indices[0] = _ij1[0];
18865 vinfos[1].indices[1] = _ij1[1];
18866 vinfos[1].maxsolutions = _nj1;
18867 vinfos[2].jointtype = 1;
18868 vinfos[2].foffset = j2;
18869 vinfos[2].indices[0] = _ij2[0];
18870 vinfos[2].indices[1] = _ij2[1];
18871 vinfos[2].maxsolutions = _nj2;
18872 vinfos[3].jointtype = 1;
18873 vinfos[3].foffset = j3;
18874 vinfos[3].indices[0] = _ij3[0];
18875 vinfos[3].indices[1] = _ij3[1];
18876 vinfos[3].maxsolutions = _nj3;
18877 vinfos[4].jointtype = 1;
18878 vinfos[4].foffset = j4;
18879 vinfos[4].indices[0] = _ij4[0];
18880 vinfos[4].indices[1] = _ij4[1];
18881 vinfos[4].maxsolutions = _nj4;
18882 vinfos[5].jointtype = 1;
18883 vinfos[5].foffset = j5;
18884 vinfos[5].indices[0] = _ij5[0];
18885 vinfos[5].indices[1] = _ij5[1];
18886 vinfos[5].maxsolutions = _nj5;
18887 std::vector<int> vfree(0);
18888 solutions.AddSolution(vinfos,vfree);
18889 }
18890 }
18891 }
18892 
18893 }
18894 
18895 }
18896 
18897 }
18898 } while(0);
18899 if( bgotonextstatement )
18900 {
18901 bool bgotonextstatement = true;
18902 do
18903 {
18904 if( 1 )
18905 {
18906 bgotonextstatement=false;
18907 continue; // branch miss [j3]
18908 
18909 }
18910 } while(0);
18911 if( bgotonextstatement )
18912 {
18913 }
18914 }
18915 }
18916 }
18917 }
18918 }
18919 }
18920 }
18921 }
18922 }
18923 }
18924 }
18925 
18926 } else
18927 {
18928 {
18929 IkReal j3array[1], cj3array[1], sj3array[1];
18930 bool j3valid[1]={false};
18931 _nj3 = 1;
18932 IkReal x1459=((1.0)*new_r00);
18933 CheckValue<IkReal> x1460 = IKatan2WithCheck(IkReal(((((-1.0)*(cj5*cj5)))+(new_r00*new_r00))),IkReal(((((-1.0)*new_r10*x1459))+((cj5*sj5)))),IKFAST_ATAN2_MAGTHRESH);
18934 if(!x1460.valid){
18935 continue;
18936 }
18937 CheckValue<IkReal> x1461=IKPowWithIntegerCheck(IKsign((((cj5*new_r10))+(((-1.0)*sj5*x1459)))),-1);
18938 if(!x1461.valid){
18939 continue;
18940 }
18941 j3array[0]=((-1.5707963267949)+(x1460.value)+(((1.5707963267949)*(x1461.value))));
18942 sj3array[0]=IKsin(j3array[0]);
18943 cj3array[0]=IKcos(j3array[0]);
18944 if( j3array[0] > IKPI )
18945 {
18946  j3array[0]-=IK2PI;
18947 }
18948 else if( j3array[0] < -IKPI )
18949 { j3array[0]+=IK2PI;
18950 }
18951 j3valid[0] = true;
18952 for(int ij3 = 0; ij3 < 1; ++ij3)
18953 {
18954 if( !j3valid[ij3] )
18955 {
18956  continue;
18957 }
18958 _ij3[0] = ij3; _ij3[1] = -1;
18959 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18960 {
18961 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18962 {
18963  j3valid[iij3]=false; _ij3[1] = iij3; break;
18964 }
18965 }
18966 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18967 {
18968 IkReal evalcond[8];
18969 IkReal x1462=IKsin(j3);
18970 IkReal x1463=IKcos(j3);
18971 IkReal x1464=((1.0)*sj5);
18972 IkReal x1465=(cj5*x1462);
18973 IkReal x1466=((1.0)*x1463);
18974 IkReal x1467=(x1463*x1464);
18975 evalcond[0]=(((new_r00*x1463))+cj5+((new_r10*x1462)));
18976 evalcond[1]=(((cj5*x1463))+new_r00+((sj5*x1462)));
18977 evalcond[2]=((((-1.0)*new_r10*x1466))+((new_r00*x1462))+sj5);
18978 evalcond[3]=(((new_r01*x1462))+cj5+(((-1.0)*new_r11*x1466)));
18979 evalcond[4]=((((-1.0)*x1467))+x1465+new_r01);
18980 evalcond[5]=((((-1.0)*x1467))+x1465+new_r10);
18981 evalcond[6]=(((new_r01*x1463))+(((-1.0)*x1464))+((new_r11*x1462)));
18982 evalcond[7]=((((-1.0)*cj5*x1466))+(((-1.0)*x1462*x1464))+new_r11);
18983 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
18984 {
18985 continue;
18986 }
18987 }
18988 
18989 {
18990 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18991 vinfos[0].jointtype = 1;
18992 vinfos[0].foffset = j0;
18993 vinfos[0].indices[0] = _ij0[0];
18994 vinfos[0].indices[1] = _ij0[1];
18995 vinfos[0].maxsolutions = _nj0;
18996 vinfos[1].jointtype = 1;
18997 vinfos[1].foffset = j1;
18998 vinfos[1].indices[0] = _ij1[0];
18999 vinfos[1].indices[1] = _ij1[1];
19000 vinfos[1].maxsolutions = _nj1;
19001 vinfos[2].jointtype = 1;
19002 vinfos[2].foffset = j2;
19003 vinfos[2].indices[0] = _ij2[0];
19004 vinfos[2].indices[1] = _ij2[1];
19005 vinfos[2].maxsolutions = _nj2;
19006 vinfos[3].jointtype = 1;
19007 vinfos[3].foffset = j3;
19008 vinfos[3].indices[0] = _ij3[0];
19009 vinfos[3].indices[1] = _ij3[1];
19010 vinfos[3].maxsolutions = _nj3;
19011 vinfos[4].jointtype = 1;
19012 vinfos[4].foffset = j4;
19013 vinfos[4].indices[0] = _ij4[0];
19014 vinfos[4].indices[1] = _ij4[1];
19015 vinfos[4].maxsolutions = _nj4;
19016 vinfos[5].jointtype = 1;
19017 vinfos[5].foffset = j5;
19018 vinfos[5].indices[0] = _ij5[0];
19019 vinfos[5].indices[1] = _ij5[1];
19020 vinfos[5].maxsolutions = _nj5;
19021 std::vector<int> vfree(0);
19022 solutions.AddSolution(vinfos,vfree);
19023 }
19024 }
19025 }
19026 
19027 }
19028 
19029 }
19030 
19031 } else
19032 {
19033 {
19034 IkReal j3array[1], cj3array[1], sj3array[1];
19035 bool j3valid[1]={false};
19036 _nj3 = 1;
19037 IkReal x1468=((1.0)*new_r10);
19038 CheckValue<IkReal> x1469 = IKatan2WithCheck(IkReal((((new_r00*new_r01))+((cj5*sj5)))),IkReal(((((-1.0)*new_r01*x1468))+(cj5*cj5))),IKFAST_ATAN2_MAGTHRESH);
19039 if(!x1469.valid){
19040 continue;
19041 }
19042 CheckValue<IkReal> x1470=IKPowWithIntegerCheck(IKsign(((((-1.0)*cj5*new_r00))+(((-1.0)*sj5*x1468)))),-1);
19043 if(!x1470.valid){
19044 continue;
19045 }
19046 j3array[0]=((-1.5707963267949)+(x1469.value)+(((1.5707963267949)*(x1470.value))));
19047 sj3array[0]=IKsin(j3array[0]);
19048 cj3array[0]=IKcos(j3array[0]);
19049 if( j3array[0] > IKPI )
19050 {
19051  j3array[0]-=IK2PI;
19052 }
19053 else if( j3array[0] < -IKPI )
19054 { j3array[0]+=IK2PI;
19055 }
19056 j3valid[0] = true;
19057 for(int ij3 = 0; ij3 < 1; ++ij3)
19058 {
19059 if( !j3valid[ij3] )
19060 {
19061  continue;
19062 }
19063 _ij3[0] = ij3; _ij3[1] = -1;
19064 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19065 {
19066 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19067 {
19068  j3valid[iij3]=false; _ij3[1] = iij3; break;
19069 }
19070 }
19071 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19072 {
19073 IkReal evalcond[8];
19074 IkReal x1471=IKsin(j3);
19075 IkReal x1472=IKcos(j3);
19076 IkReal x1473=((1.0)*sj5);
19077 IkReal x1474=(cj5*x1471);
19078 IkReal x1475=((1.0)*x1472);
19079 IkReal x1476=(x1472*x1473);
19080 evalcond[0]=(((new_r10*x1471))+cj5+((new_r00*x1472)));
19081 evalcond[1]=(((cj5*x1472))+((sj5*x1471))+new_r00);
19082 evalcond[2]=(sj5+((new_r00*x1471))+(((-1.0)*new_r10*x1475)));
19083 evalcond[3]=(cj5+(((-1.0)*new_r11*x1475))+((new_r01*x1471)));
19084 evalcond[4]=(x1474+(((-1.0)*x1476))+new_r01);
19085 evalcond[5]=(x1474+(((-1.0)*x1476))+new_r10);
19086 evalcond[6]=(((new_r11*x1471))+((new_r01*x1472))+(((-1.0)*x1473)));
19087 evalcond[7]=((((-1.0)*x1471*x1473))+(((-1.0)*cj5*x1475))+new_r11);
19088 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
19089 {
19090 continue;
19091 }
19092 }
19093 
19094 {
19095 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19096 vinfos[0].jointtype = 1;
19097 vinfos[0].foffset = j0;
19098 vinfos[0].indices[0] = _ij0[0];
19099 vinfos[0].indices[1] = _ij0[1];
19100 vinfos[0].maxsolutions = _nj0;
19101 vinfos[1].jointtype = 1;
19102 vinfos[1].foffset = j1;
19103 vinfos[1].indices[0] = _ij1[0];
19104 vinfos[1].indices[1] = _ij1[1];
19105 vinfos[1].maxsolutions = _nj1;
19106 vinfos[2].jointtype = 1;
19107 vinfos[2].foffset = j2;
19108 vinfos[2].indices[0] = _ij2[0];
19109 vinfos[2].indices[1] = _ij2[1];
19110 vinfos[2].maxsolutions = _nj2;
19111 vinfos[3].jointtype = 1;
19112 vinfos[3].foffset = j3;
19113 vinfos[3].indices[0] = _ij3[0];
19114 vinfos[3].indices[1] = _ij3[1];
19115 vinfos[3].maxsolutions = _nj3;
19116 vinfos[4].jointtype = 1;
19117 vinfos[4].foffset = j4;
19118 vinfos[4].indices[0] = _ij4[0];
19119 vinfos[4].indices[1] = _ij4[1];
19120 vinfos[4].maxsolutions = _nj4;
19121 vinfos[5].jointtype = 1;
19122 vinfos[5].foffset = j5;
19123 vinfos[5].indices[0] = _ij5[0];
19124 vinfos[5].indices[1] = _ij5[1];
19125 vinfos[5].maxsolutions = _nj5;
19126 std::vector<int> vfree(0);
19127 solutions.AddSolution(vinfos,vfree);
19128 }
19129 }
19130 }
19131 
19132 }
19133 
19134 }
19135 
19136 } else
19137 {
19138 {
19139 IkReal j3array[1], cj3array[1], sj3array[1];
19140 bool j3valid[1]={false};
19141 _nj3 = 1;
19142 IkReal x1477=((1.0)*new_r10);
19143 CheckValue<IkReal> x1478 = IKatan2WithCheck(IkReal((((cj5*new_r11))+((cj5*new_r00)))),IkReal((((cj5*new_r01))+(((-1.0)*cj5*x1477)))),IKFAST_ATAN2_MAGTHRESH);
19144 if(!x1478.valid){
19145 continue;
19146 }
19147 CheckValue<IkReal> x1479=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r11*x1477))+(((-1.0)*new_r00*new_r01)))),-1);
19148 if(!x1479.valid){
19149 continue;
19150 }
19151 j3array[0]=((-1.5707963267949)+(x1478.value)+(((1.5707963267949)*(x1479.value))));
19152 sj3array[0]=IKsin(j3array[0]);
19153 cj3array[0]=IKcos(j3array[0]);
19154 if( j3array[0] > IKPI )
19155 {
19156  j3array[0]-=IK2PI;
19157 }
19158 else if( j3array[0] < -IKPI )
19159 { j3array[0]+=IK2PI;
19160 }
19161 j3valid[0] = true;
19162 for(int ij3 = 0; ij3 < 1; ++ij3)
19163 {
19164 if( !j3valid[ij3] )
19165 {
19166  continue;
19167 }
19168 _ij3[0] = ij3; _ij3[1] = -1;
19169 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19170 {
19171 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19172 {
19173  j3valid[iij3]=false; _ij3[1] = iij3; break;
19174 }
19175 }
19176 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19177 {
19178 IkReal evalcond[8];
19179 IkReal x1480=IKsin(j3);
19180 IkReal x1481=IKcos(j3);
19181 IkReal x1482=((1.0)*sj5);
19182 IkReal x1483=(cj5*x1480);
19183 IkReal x1484=((1.0)*x1481);
19184 IkReal x1485=(x1481*x1482);
19185 evalcond[0]=(cj5+((new_r00*x1481))+((new_r10*x1480)));
19186 evalcond[1]=(((cj5*x1481))+new_r00+((sj5*x1480)));
19187 evalcond[2]=(sj5+(((-1.0)*new_r10*x1484))+((new_r00*x1480)));
19188 evalcond[3]=(cj5+(((-1.0)*new_r11*x1484))+((new_r01*x1480)));
19189 evalcond[4]=((((-1.0)*x1485))+x1483+new_r01);
19190 evalcond[5]=((((-1.0)*x1485))+x1483+new_r10);
19191 evalcond[6]=((((-1.0)*x1482))+((new_r11*x1480))+((new_r01*x1481)));
19192 evalcond[7]=((((-1.0)*x1480*x1482))+new_r11+(((-1.0)*cj5*x1484)));
19193 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
19194 {
19195 continue;
19196 }
19197 }
19198 
19199 {
19200 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19201 vinfos[0].jointtype = 1;
19202 vinfos[0].foffset = j0;
19203 vinfos[0].indices[0] = _ij0[0];
19204 vinfos[0].indices[1] = _ij0[1];
19205 vinfos[0].maxsolutions = _nj0;
19206 vinfos[1].jointtype = 1;
19207 vinfos[1].foffset = j1;
19208 vinfos[1].indices[0] = _ij1[0];
19209 vinfos[1].indices[1] = _ij1[1];
19210 vinfos[1].maxsolutions = _nj1;
19211 vinfos[2].jointtype = 1;
19212 vinfos[2].foffset = j2;
19213 vinfos[2].indices[0] = _ij2[0];
19214 vinfos[2].indices[1] = _ij2[1];
19215 vinfos[2].maxsolutions = _nj2;
19216 vinfos[3].jointtype = 1;
19217 vinfos[3].foffset = j3;
19218 vinfos[3].indices[0] = _ij3[0];
19219 vinfos[3].indices[1] = _ij3[1];
19220 vinfos[3].maxsolutions = _nj3;
19221 vinfos[4].jointtype = 1;
19222 vinfos[4].foffset = j4;
19223 vinfos[4].indices[0] = _ij4[0];
19224 vinfos[4].indices[1] = _ij4[1];
19225 vinfos[4].maxsolutions = _nj4;
19226 vinfos[5].jointtype = 1;
19227 vinfos[5].foffset = j5;
19228 vinfos[5].indices[0] = _ij5[0];
19229 vinfos[5].indices[1] = _ij5[1];
19230 vinfos[5].maxsolutions = _nj5;
19231 std::vector<int> vfree(0);
19232 solutions.AddSolution(vinfos,vfree);
19233 }
19234 }
19235 }
19236 
19237 }
19238 
19239 }
19240 
19241 }
19242 } while(0);
19243 if( bgotonextstatement )
19244 {
19245 bool bgotonextstatement = true;
19246 do
19247 {
19248 evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02)));
19249 if( IKabs(evalcond[0]) < 0.0000050000000000 )
19250 {
19251 bgotonextstatement=false;
19252 {
19253 IkReal j3eval[1];
19254 new_r02=0;
19255 new_r12=0;
19256 new_r20=0;
19257 new_r21=0;
19258 j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
19259 if( IKabs(j3eval[0]) < 0.0000010000000000 )
19260 {
19261 {
19262 IkReal j3eval[1];
19263 new_r02=0;
19264 new_r12=0;
19265 new_r20=0;
19266 new_r21=0;
19267 j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
19268 if( IKabs(j3eval[0]) < 0.0000010000000000 )
19269 {
19270 {
19271 IkReal j3eval[1];
19272 new_r02=0;
19273 new_r12=0;
19274 new_r20=0;
19275 new_r21=0;
19276 j3eval[0]=((IKabs((new_r10*new_r22)))+(IKabs((new_r00*new_r22))));
19277 if( IKabs(j3eval[0]) < 0.0000010000000000 )
19278 {
19279 continue; // no branches [j3]
19280 
19281 } else
19282 {
19283 {
19284 IkReal j3array[2], cj3array[2], sj3array[2];
19285 bool j3valid[2]={false};
19286 _nj3 = 2;
19287 IkReal x1486=((-1.0)*new_r22);
19288 CheckValue<IkReal> x1488 = IKatan2WithCheck(IkReal((new_r00*x1486)),IkReal((new_r10*x1486)),IKFAST_ATAN2_MAGTHRESH);
19289 if(!x1488.valid){
19290 continue;
19291 }
19292 IkReal x1487=x1488.value;
19293 j3array[0]=((-1.0)*x1487);
19294 sj3array[0]=IKsin(j3array[0]);
19295 cj3array[0]=IKcos(j3array[0]);
19296 j3array[1]=((3.14159265358979)+(((-1.0)*x1487)));
19297 sj3array[1]=IKsin(j3array[1]);
19298 cj3array[1]=IKcos(j3array[1]);
19299 if( j3array[0] > IKPI )
19300 {
19301  j3array[0]-=IK2PI;
19302 }
19303 else if( j3array[0] < -IKPI )
19304 { j3array[0]+=IK2PI;
19305 }
19306 j3valid[0] = true;
19307 if( j3array[1] > IKPI )
19308 {
19309  j3array[1]-=IK2PI;
19310 }
19311 else if( j3array[1] < -IKPI )
19312 { j3array[1]+=IK2PI;
19313 }
19314 j3valid[1] = true;
19315 for(int ij3 = 0; ij3 < 2; ++ij3)
19316 {
19317 if( !j3valid[ij3] )
19318 {
19319  continue;
19320 }
19321 _ij3[0] = ij3; _ij3[1] = -1;
19322 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
19323 {
19324 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19325 {
19326  j3valid[iij3]=false; _ij3[1] = iij3; break;
19327 }
19328 }
19329 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19330 {
19331 IkReal evalcond[5];
19332 IkReal x1489=IKsin(j3);
19333 IkReal x1490=IKcos(j3);
19334 IkReal x1491=((1.0)*new_r11);
19335 IkReal x1492=(new_r01*x1490);
19336 evalcond[0]=(((new_r11*x1489))+x1492);
19337 evalcond[1]=(((new_r00*x1490))+((new_r10*x1489)));
19338 evalcond[2]=(((new_r00*x1489))+(((-1.0)*new_r10*x1490)));
19339 evalcond[3]=(((new_r01*x1489))+(((-1.0)*x1490*x1491)));
19340 evalcond[4]=((((-1.0)*new_r22*x1492))+(((-1.0)*new_r22*x1489*x1491)));
19341 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
19342 {
19343 continue;
19344 }
19345 }
19346 
19347 {
19348 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19349 vinfos[0].jointtype = 1;
19350 vinfos[0].foffset = j0;
19351 vinfos[0].indices[0] = _ij0[0];
19352 vinfos[0].indices[1] = _ij0[1];
19353 vinfos[0].maxsolutions = _nj0;
19354 vinfos[1].jointtype = 1;
19355 vinfos[1].foffset = j1;
19356 vinfos[1].indices[0] = _ij1[0];
19357 vinfos[1].indices[1] = _ij1[1];
19358 vinfos[1].maxsolutions = _nj1;
19359 vinfos[2].jointtype = 1;
19360 vinfos[2].foffset = j2;
19361 vinfos[2].indices[0] = _ij2[0];
19362 vinfos[2].indices[1] = _ij2[1];
19363 vinfos[2].maxsolutions = _nj2;
19364 vinfos[3].jointtype = 1;
19365 vinfos[3].foffset = j3;
19366 vinfos[3].indices[0] = _ij3[0];
19367 vinfos[3].indices[1] = _ij3[1];
19368 vinfos[3].maxsolutions = _nj3;
19369 vinfos[4].jointtype = 1;
19370 vinfos[4].foffset = j4;
19371 vinfos[4].indices[0] = _ij4[0];
19372 vinfos[4].indices[1] = _ij4[1];
19373 vinfos[4].maxsolutions = _nj4;
19374 vinfos[5].jointtype = 1;
19375 vinfos[5].foffset = j5;
19376 vinfos[5].indices[0] = _ij5[0];
19377 vinfos[5].indices[1] = _ij5[1];
19378 vinfos[5].maxsolutions = _nj5;
19379 std::vector<int> vfree(0);
19380 solutions.AddSolution(vinfos,vfree);
19381 }
19382 }
19383 }
19384 
19385 }
19386 
19387 }
19388 
19389 } else
19390 {
19391 {
19392 IkReal j3array[2], cj3array[2], sj3array[2];
19393 bool j3valid[2]={false};
19394 _nj3 = 2;
19395 CheckValue<IkReal> x1494 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
19396 if(!x1494.valid){
19397 continue;
19398 }
19399 IkReal x1493=x1494.value;
19400 j3array[0]=((-1.0)*x1493);
19401 sj3array[0]=IKsin(j3array[0]);
19402 cj3array[0]=IKcos(j3array[0]);
19403 j3array[1]=((3.14159265358979)+(((-1.0)*x1493)));
19404 sj3array[1]=IKsin(j3array[1]);
19405 cj3array[1]=IKcos(j3array[1]);
19406 if( j3array[0] > IKPI )
19407 {
19408  j3array[0]-=IK2PI;
19409 }
19410 else if( j3array[0] < -IKPI )
19411 { j3array[0]+=IK2PI;
19412 }
19413 j3valid[0] = true;
19414 if( j3array[1] > IKPI )
19415 {
19416  j3array[1]-=IK2PI;
19417 }
19418 else if( j3array[1] < -IKPI )
19419 { j3array[1]+=IK2PI;
19420 }
19421 j3valid[1] = true;
19422 for(int ij3 = 0; ij3 < 2; ++ij3)
19423 {
19424 if( !j3valid[ij3] )
19425 {
19426  continue;
19427 }
19428 _ij3[0] = ij3; _ij3[1] = -1;
19429 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
19430 {
19431 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19432 {
19433  j3valid[iij3]=false; _ij3[1] = iij3; break;
19434 }
19435 }
19436 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19437 {
19438 IkReal evalcond[5];
19439 IkReal x1495=IKsin(j3);
19440 IkReal x1496=IKcos(j3);
19441 IkReal x1497=((1.0)*x1496);
19442 IkReal x1498=((1.0)*new_r22*x1495);
19443 evalcond[0]=(((new_r01*x1496))+((new_r11*x1495)));
19444 evalcond[1]=((((-1.0)*new_r10*x1497))+((new_r00*x1495)));
19445 evalcond[2]=(((new_r01*x1495))+(((-1.0)*new_r11*x1497)));
19446 evalcond[3]=((((-1.0)*new_r10*x1498))+(((-1.0)*new_r00*new_r22*x1497)));
19447 evalcond[4]=((((-1.0)*new_r11*x1498))+(((-1.0)*new_r01*new_r22*x1497)));
19448 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
19449 {
19450 continue;
19451 }
19452 }
19453 
19454 {
19455 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19456 vinfos[0].jointtype = 1;
19457 vinfos[0].foffset = j0;
19458 vinfos[0].indices[0] = _ij0[0];
19459 vinfos[0].indices[1] = _ij0[1];
19460 vinfos[0].maxsolutions = _nj0;
19461 vinfos[1].jointtype = 1;
19462 vinfos[1].foffset = j1;
19463 vinfos[1].indices[0] = _ij1[0];
19464 vinfos[1].indices[1] = _ij1[1];
19465 vinfos[1].maxsolutions = _nj1;
19466 vinfos[2].jointtype = 1;
19467 vinfos[2].foffset = j2;
19468 vinfos[2].indices[0] = _ij2[0];
19469 vinfos[2].indices[1] = _ij2[1];
19470 vinfos[2].maxsolutions = _nj2;
19471 vinfos[3].jointtype = 1;
19472 vinfos[3].foffset = j3;
19473 vinfos[3].indices[0] = _ij3[0];
19474 vinfos[3].indices[1] = _ij3[1];
19475 vinfos[3].maxsolutions = _nj3;
19476 vinfos[4].jointtype = 1;
19477 vinfos[4].foffset = j4;
19478 vinfos[4].indices[0] = _ij4[0];
19479 vinfos[4].indices[1] = _ij4[1];
19480 vinfos[4].maxsolutions = _nj4;
19481 vinfos[5].jointtype = 1;
19482 vinfos[5].foffset = j5;
19483 vinfos[5].indices[0] = _ij5[0];
19484 vinfos[5].indices[1] = _ij5[1];
19485 vinfos[5].maxsolutions = _nj5;
19486 std::vector<int> vfree(0);
19487 solutions.AddSolution(vinfos,vfree);
19488 }
19489 }
19490 }
19491 
19492 }
19493 
19494 }
19495 
19496 } else
19497 {
19498 {
19499 IkReal j3array[2], cj3array[2], sj3array[2];
19500 bool j3valid[2]={false};
19501 _nj3 = 2;
19502 CheckValue<IkReal> x1500 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
19503 if(!x1500.valid){
19504 continue;
19505 }
19506 IkReal x1499=x1500.value;
19507 j3array[0]=((-1.0)*x1499);
19508 sj3array[0]=IKsin(j3array[0]);
19509 cj3array[0]=IKcos(j3array[0]);
19510 j3array[1]=((3.14159265358979)+(((-1.0)*x1499)));
19511 sj3array[1]=IKsin(j3array[1]);
19512 cj3array[1]=IKcos(j3array[1]);
19513 if( j3array[0] > IKPI )
19514 {
19515  j3array[0]-=IK2PI;
19516 }
19517 else if( j3array[0] < -IKPI )
19518 { j3array[0]+=IK2PI;
19519 }
19520 j3valid[0] = true;
19521 if( j3array[1] > IKPI )
19522 {
19523  j3array[1]-=IK2PI;
19524 }
19525 else if( j3array[1] < -IKPI )
19526 { j3array[1]+=IK2PI;
19527 }
19528 j3valid[1] = true;
19529 for(int ij3 = 0; ij3 < 2; ++ij3)
19530 {
19531 if( !j3valid[ij3] )
19532 {
19533  continue;
19534 }
19535 _ij3[0] = ij3; _ij3[1] = -1;
19536 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
19537 {
19538 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19539 {
19540  j3valid[iij3]=false; _ij3[1] = iij3; break;
19541 }
19542 }
19543 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19544 {
19545 IkReal evalcond[5];
19546 IkReal x1501=IKsin(j3);
19547 IkReal x1502=IKcos(j3);
19548 IkReal x1503=((1.0)*new_r22);
19549 IkReal x1504=(new_r10*x1501);
19550 IkReal x1505=((1.0)*x1502);
19551 IkReal x1506=(new_r00*x1502);
19552 evalcond[0]=(x1506+x1504);
19553 evalcond[1]=((((-1.0)*new_r10*x1505))+((new_r00*x1501)));
19554 evalcond[2]=((((-1.0)*new_r11*x1505))+((new_r01*x1501)));
19555 evalcond[3]=((((-1.0)*x1503*x1506))+(((-1.0)*x1503*x1504)));
19556 evalcond[4]=((((-1.0)*new_r11*x1501*x1503))+(((-1.0)*new_r01*x1502*x1503)));
19557 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
19558 {
19559 continue;
19560 }
19561 }
19562 
19563 {
19564 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19565 vinfos[0].jointtype = 1;
19566 vinfos[0].foffset = j0;
19567 vinfos[0].indices[0] = _ij0[0];
19568 vinfos[0].indices[1] = _ij0[1];
19569 vinfos[0].maxsolutions = _nj0;
19570 vinfos[1].jointtype = 1;
19571 vinfos[1].foffset = j1;
19572 vinfos[1].indices[0] = _ij1[0];
19573 vinfos[1].indices[1] = _ij1[1];
19574 vinfos[1].maxsolutions = _nj1;
19575 vinfos[2].jointtype = 1;
19576 vinfos[2].foffset = j2;
19577 vinfos[2].indices[0] = _ij2[0];
19578 vinfos[2].indices[1] = _ij2[1];
19579 vinfos[2].maxsolutions = _nj2;
19580 vinfos[3].jointtype = 1;
19581 vinfos[3].foffset = j3;
19582 vinfos[3].indices[0] = _ij3[0];
19583 vinfos[3].indices[1] = _ij3[1];
19584 vinfos[3].maxsolutions = _nj3;
19585 vinfos[4].jointtype = 1;
19586 vinfos[4].foffset = j4;
19587 vinfos[4].indices[0] = _ij4[0];
19588 vinfos[4].indices[1] = _ij4[1];
19589 vinfos[4].maxsolutions = _nj4;
19590 vinfos[5].jointtype = 1;
19591 vinfos[5].foffset = j5;
19592 vinfos[5].indices[0] = _ij5[0];
19593 vinfos[5].indices[1] = _ij5[1];
19594 vinfos[5].maxsolutions = _nj5;
19595 std::vector<int> vfree(0);
19596 solutions.AddSolution(vinfos,vfree);
19597 }
19598 }
19599 }
19600 
19601 }
19602 
19603 }
19604 
19605 }
19606 } while(0);
19607 if( bgotonextstatement )
19608 {
19609 bool bgotonextstatement = true;
19610 do
19611 {
19612 if( 1 )
19613 {
19614 bgotonextstatement=false;
19615 continue; // branch miss [j3]
19616 
19617 }
19618 } while(0);
19619 if( bgotonextstatement )
19620 {
19621 }
19622 }
19623 }
19624 }
19625 }
19626 
19627 } else
19628 {
19629 {
19630 IkReal j3array[1], cj3array[1], sj3array[1];
19631 bool j3valid[1]={false};
19632 _nj3 = 1;
19634 if(!x1508.valid){
19635 continue;
19636 }
19637 IkReal x1507=x1508.value;
19638 CheckValue<IkReal> x1509=IKPowWithIntegerCheck(new_r12,-1);
19639 if(!x1509.valid){
19640 continue;
19641 }
19642 if( IKabs((x1507*(x1509.value)*(((-1.0)+(new_r02*new_r02)+(cj4*cj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r02*x1507)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x1507*(x1509.value)*(((-1.0)+(new_r02*new_r02)+(cj4*cj4)))))+IKsqr(((-1.0)*new_r02*x1507))-1) <= IKFAST_SINCOS_THRESH )
19643  continue;
19644 j3array[0]=IKatan2((x1507*(x1509.value)*(((-1.0)+(new_r02*new_r02)+(cj4*cj4)))), ((-1.0)*new_r02*x1507));
19645 sj3array[0]=IKsin(j3array[0]);
19646 cj3array[0]=IKcos(j3array[0]);
19647 if( j3array[0] > IKPI )
19648 {
19649  j3array[0]-=IK2PI;
19650 }
19651 else if( j3array[0] < -IKPI )
19652 { j3array[0]+=IK2PI;
19653 }
19654 j3valid[0] = true;
19655 for(int ij3 = 0; ij3 < 1; ++ij3)
19656 {
19657 if( !j3valid[ij3] )
19658 {
19659  continue;
19660 }
19661 _ij3[0] = ij3; _ij3[1] = -1;
19662 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19663 {
19664 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19665 {
19666  j3valid[iij3]=false; _ij3[1] = iij3; break;
19667 }
19668 }
19669 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19670 {
19671 IkReal evalcond[18];
19672 IkReal x1510=IKcos(j3);
19673 IkReal x1511=IKsin(j3);
19674 IkReal x1512=(cj4*cj5);
19675 IkReal x1513=(cj4*sj5);
19676 IkReal x1514=((1.0)*new_r20);
19677 IkReal x1515=((1.0)*cj4);
19678 IkReal x1516=((1.0)*sj4);
19679 IkReal x1517=(sj4*x1511);
19680 IkReal x1518=((1.0)*x1510);
19681 IkReal x1519=(sj4*x1510);
19682 IkReal x1520=(x1511*x1515);
19683 evalcond[0]=(x1519+new_r02);
19684 evalcond[1]=(x1517+new_r12);
19685 evalcond[2]=((((-1.0)*new_r02*x1511))+((new_r12*x1510)));
19686 evalcond[3]=(sj4+((new_r02*x1510))+((new_r12*x1511)));
19687 evalcond[4]=(sj5+(((-1.0)*new_r10*x1518))+((new_r00*x1511)));
19688 evalcond[5]=((((-1.0)*new_r11*x1518))+cj5+((new_r01*x1511)));
19689 evalcond[6]=(((x1510*x1513))+((cj5*x1511))+new_r01);
19690 evalcond[7]=(x1513+((new_r01*x1510))+((new_r11*x1511)));
19691 evalcond[8]=(((sj5*x1511))+(((-1.0)*x1512*x1518))+new_r00);
19692 evalcond[9]=((((-1.0)*cj5*x1518))+new_r11+((x1511*x1513)));
19693 evalcond[10]=(((new_r10*x1511))+(((-1.0)*x1512))+((new_r00*x1510)));
19694 evalcond[11]=((((-1.0)*x1511*x1512))+(((-1.0)*sj5*x1518))+new_r10);
19695 evalcond[12]=(((new_r10*x1517))+(((-1.0)*cj4*x1514))+((new_r00*x1519)));
19696 evalcond[13]=((((-1.0)*new_r21*x1515))+((new_r01*x1519))+((new_r11*x1517)));
19697 evalcond[14]=((1.0)+(((-1.0)*new_r22*x1515))+((new_r02*x1519))+((new_r12*x1517)));
19698 evalcond[15]=((((-1.0)*new_r22*x1516))+(((-1.0)*new_r12*x1520))+(((-1.0)*new_r02*x1510*x1515)));
19699 evalcond[16]=(cj5+(((-1.0)*new_r00*x1510*x1515))+(((-1.0)*sj4*x1514))+(((-1.0)*new_r10*x1520)));
19700 evalcond[17]=((((-1.0)*sj5))+(((-1.0)*new_r11*x1520))+(((-1.0)*new_r21*x1516))+(((-1.0)*new_r01*x1510*x1515)));
19701 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
19702 {
19703 continue;
19704 }
19705 }
19706 
19707 {
19708 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19709 vinfos[0].jointtype = 1;
19710 vinfos[0].foffset = j0;
19711 vinfos[0].indices[0] = _ij0[0];
19712 vinfos[0].indices[1] = _ij0[1];
19713 vinfos[0].maxsolutions = _nj0;
19714 vinfos[1].jointtype = 1;
19715 vinfos[1].foffset = j1;
19716 vinfos[1].indices[0] = _ij1[0];
19717 vinfos[1].indices[1] = _ij1[1];
19718 vinfos[1].maxsolutions = _nj1;
19719 vinfos[2].jointtype = 1;
19720 vinfos[2].foffset = j2;
19721 vinfos[2].indices[0] = _ij2[0];
19722 vinfos[2].indices[1] = _ij2[1];
19723 vinfos[2].maxsolutions = _nj2;
19724 vinfos[3].jointtype = 1;
19725 vinfos[3].foffset = j3;
19726 vinfos[3].indices[0] = _ij3[0];
19727 vinfos[3].indices[1] = _ij3[1];
19728 vinfos[3].maxsolutions = _nj3;
19729 vinfos[4].jointtype = 1;
19730 vinfos[4].foffset = j4;
19731 vinfos[4].indices[0] = _ij4[0];
19732 vinfos[4].indices[1] = _ij4[1];
19733 vinfos[4].maxsolutions = _nj4;
19734 vinfos[5].jointtype = 1;
19735 vinfos[5].foffset = j5;
19736 vinfos[5].indices[0] = _ij5[0];
19737 vinfos[5].indices[1] = _ij5[1];
19738 vinfos[5].maxsolutions = _nj5;
19739 std::vector<int> vfree(0);
19740 solutions.AddSolution(vinfos,vfree);
19741 }
19742 }
19743 }
19744 
19745 }
19746 
19747 }
19748 
19749 } else
19750 {
19751 {
19752 IkReal j3array[1], cj3array[1], sj3array[1];
19753 bool j3valid[1]={false};
19754 _nj3 = 1;
19756 if(!x1521.valid){
19757 continue;
19758 }
19759 CheckValue<IkReal> x1522 = IKatan2WithCheck(IkReal(((-1.0)*new_r12)),IkReal(((-1.0)*new_r02)),IKFAST_ATAN2_MAGTHRESH);
19760 if(!x1522.valid){
19761 continue;
19762 }
19763 j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1521.value)))+(x1522.value));
19764 sj3array[0]=IKsin(j3array[0]);
19765 cj3array[0]=IKcos(j3array[0]);
19766 if( j3array[0] > IKPI )
19767 {
19768  j3array[0]-=IK2PI;
19769 }
19770 else if( j3array[0] < -IKPI )
19771 { j3array[0]+=IK2PI;
19772 }
19773 j3valid[0] = true;
19774 for(int ij3 = 0; ij3 < 1; ++ij3)
19775 {
19776 if( !j3valid[ij3] )
19777 {
19778  continue;
19779 }
19780 _ij3[0] = ij3; _ij3[1] = -1;
19781 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19782 {
19783 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19784 {
19785  j3valid[iij3]=false; _ij3[1] = iij3; break;
19786 }
19787 }
19788 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19789 {
19790 IkReal evalcond[18];
19791 IkReal x1523=IKcos(j3);
19792 IkReal x1524=IKsin(j3);
19793 IkReal x1525=(cj4*cj5);
19794 IkReal x1526=(cj4*sj5);
19795 IkReal x1527=((1.0)*new_r20);
19796 IkReal x1528=((1.0)*cj4);
19797 IkReal x1529=((1.0)*sj4);
19798 IkReal x1530=(sj4*x1524);
19799 IkReal x1531=((1.0)*x1523);
19800 IkReal x1532=(sj4*x1523);
19801 IkReal x1533=(x1524*x1528);
19802 evalcond[0]=(x1532+new_r02);
19803 evalcond[1]=(x1530+new_r12);
19804 evalcond[2]=(((new_r12*x1523))+(((-1.0)*new_r02*x1524)));
19805 evalcond[3]=(((new_r12*x1524))+sj4+((new_r02*x1523)));
19806 evalcond[4]=((((-1.0)*new_r10*x1531))+sj5+((new_r00*x1524)));
19807 evalcond[5]=(cj5+((new_r01*x1524))+(((-1.0)*new_r11*x1531)));
19808 evalcond[6]=(((x1523*x1526))+((cj5*x1524))+new_r01);
19809 evalcond[7]=(((new_r01*x1523))+x1526+((new_r11*x1524)));
19810 evalcond[8]=(((sj5*x1524))+(((-1.0)*x1525*x1531))+new_r00);
19811 evalcond[9]=(((x1524*x1526))+(((-1.0)*cj5*x1531))+new_r11);
19812 evalcond[10]=(((new_r00*x1523))+((new_r10*x1524))+(((-1.0)*x1525)));
19813 evalcond[11]=((((-1.0)*x1524*x1525))+new_r10+(((-1.0)*sj5*x1531)));
19814 evalcond[12]=((((-1.0)*cj4*x1527))+((new_r00*x1532))+((new_r10*x1530)));
19815 evalcond[13]=((((-1.0)*new_r21*x1528))+((new_r01*x1532))+((new_r11*x1530)));
19816 evalcond[14]=((1.0)+((new_r02*x1532))+(((-1.0)*new_r22*x1528))+((new_r12*x1530)));
19817 evalcond[15]=((((-1.0)*new_r02*x1523*x1528))+(((-1.0)*new_r22*x1529))+(((-1.0)*new_r12*x1533)));
19818 evalcond[16]=((((-1.0)*new_r10*x1533))+(((-1.0)*sj4*x1527))+cj5+(((-1.0)*new_r00*x1523*x1528)));
19819 evalcond[17]=((((-1.0)*sj5))+(((-1.0)*new_r21*x1529))+(((-1.0)*new_r01*x1523*x1528))+(((-1.0)*new_r11*x1533)));
19820 if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
19821 {
19822 continue;
19823 }
19824 }
19825 
19826 {
19827 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19828 vinfos[0].jointtype = 1;
19829 vinfos[0].foffset = j0;
19830 vinfos[0].indices[0] = _ij0[0];
19831 vinfos[0].indices[1] = _ij0[1];
19832 vinfos[0].maxsolutions = _nj0;
19833 vinfos[1].jointtype = 1;
19834 vinfos[1].foffset = j1;
19835 vinfos[1].indices[0] = _ij1[0];
19836 vinfos[1].indices[1] = _ij1[1];
19837 vinfos[1].maxsolutions = _nj1;
19838 vinfos[2].jointtype = 1;
19839 vinfos[2].foffset = j2;
19840 vinfos[2].indices[0] = _ij2[0];
19841 vinfos[2].indices[1] = _ij2[1];
19842 vinfos[2].maxsolutions = _nj2;
19843 vinfos[3].jointtype = 1;
19844 vinfos[3].foffset = j3;
19845 vinfos[3].indices[0] = _ij3[0];
19846 vinfos[3].indices[1] = _ij3[1];
19847 vinfos[3].maxsolutions = _nj3;
19848 vinfos[4].jointtype = 1;
19849 vinfos[4].foffset = j4;
19850 vinfos[4].indices[0] = _ij4[0];
19851 vinfos[4].indices[1] = _ij4[1];
19852 vinfos[4].maxsolutions = _nj4;
19853 vinfos[5].jointtype = 1;
19854 vinfos[5].foffset = j5;
19855 vinfos[5].indices[0] = _ij5[0];
19856 vinfos[5].indices[1] = _ij5[1];
19857 vinfos[5].maxsolutions = _nj5;
19858 std::vector<int> vfree(0);
19859 solutions.AddSolution(vinfos,vfree);
19860 }
19861 }
19862 }
19863 
19864 }
19865 
19866 }
19867 }
19868 }
19869 
19870 }
19871 
19872 }
19873 }
19874 }
19875 }
19876 }static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots)
19877 {
19878  using std::complex;
19879  if( rawcoeffs[0] == 0 ) {
19880  // solve with one reduced degree
19881  polyroots2(&rawcoeffs[1], &rawroots[0], numroots);
19882  return;
19883  }
19884  IKFAST_ASSERT(rawcoeffs[0] != 0);
19885  const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
19886  const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
19887  complex<IkReal> coeffs[3];
19888  const int maxsteps = 110;
19889  for(int i = 0; i < 3; ++i) {
19890  coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
19891  }
19892  complex<IkReal> roots[3];
19893  IkReal err[3];
19894  roots[0] = complex<IkReal>(1,0);
19895  roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
19896  err[0] = 1.0;
19897  err[1] = 1.0;
19898  for(int i = 2; i < 3; ++i) {
19899  roots[i] = roots[i-1]*roots[1];
19900  err[i] = 1.0;
19901  }
19902  for(int step = 0; step < maxsteps; ++step) {
19903  bool changed = false;
19904  for(int i = 0; i < 3; ++i) {
19905  if ( err[i] >= tol ) {
19906  changed = true;
19907  // evaluate
19908  complex<IkReal> x = roots[i] + coeffs[0];
19909  for(int j = 1; j < 3; ++j) {
19910  x = roots[i] * x + coeffs[j];
19911  }
19912  for(int j = 0; j < 3; ++j) {
19913  if( i != j ) {
19914  if( roots[i] != roots[j] ) {
19915  x /= (roots[i] - roots[j]);
19916  }
19917  }
19918  }
19919  roots[i] -= x;
19920  err[i] = abs(x);
19921  }
19922  }
19923  if( !changed ) {
19924  break;
19925  }
19926  }
19927 
19928  numroots = 0;
19929  bool visited[3] = {false};
19930  for(int i = 0; i < 3; ++i) {
19931  if( !visited[i] ) {
19932  // might be a multiple root, in which case it will have more error than the other roots
19933  // find any neighboring roots, and take the average
19934  complex<IkReal> newroot=roots[i];
19935  int n = 1;
19936  for(int j = i+1; j < 3; ++j) {
19937  // care about error in real much more than imaginary
19938  if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
19939  newroot += roots[j];
19940  n += 1;
19941  visited[j] = true;
19942  }
19943  }
19944  if( n > 1 ) {
19945  newroot /= n;
19946  }
19947  // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt
19948  if( IKabs(imag(newroot)) < tolsqrt ) {
19949  rawroots[numroots++] = real(newroot);
19950  }
19951  }
19952  }
19953 }
19954 static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) {
19955  IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2];
19956  if( det < 0 ) {
19957  numroots=0;
19958  }
19959  else if( det == 0 ) {
19960  rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0];
19961  numroots = 1;
19962  }
19963  else {
19964  det = IKsqrt(det);
19965  rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]);
19966  rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]);
19967  numroots = 2;
19968  }
19969 }
19970 static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
19971 {
19972  using std::complex;
19973  if( rawcoeffs[0] == 0 ) {
19974  // solve with one reduced degree
19975  polyroots3(&rawcoeffs[1], &rawroots[0], numroots);
19976  return;
19977  }
19978  IKFAST_ASSERT(rawcoeffs[0] != 0);
19979  const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
19980  const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
19981  complex<IkReal> coeffs[4];
19982  const int maxsteps = 110;
19983  for(int i = 0; i < 4; ++i) {
19984  coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
19985  }
19986  complex<IkReal> roots[4];
19987  IkReal err[4];
19988  roots[0] = complex<IkReal>(1,0);
19989  roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
19990  err[0] = 1.0;
19991  err[1] = 1.0;
19992  for(int i = 2; i < 4; ++i) {
19993  roots[i] = roots[i-1]*roots[1];
19994  err[i] = 1.0;
19995  }
19996  for(int step = 0; step < maxsteps; ++step) {
19997  bool changed = false;
19998  for(int i = 0; i < 4; ++i) {
19999  if ( err[i] >= tol ) {
20000  changed = true;
20001  // evaluate
20002  complex<IkReal> x = roots[i] + coeffs[0];
20003  for(int j = 1; j < 4; ++j) {
20004  x = roots[i] * x + coeffs[j];
20005  }
20006  for(int j = 0; j < 4; ++j) {
20007  if( i != j ) {
20008  if( roots[i] != roots[j] ) {
20009  x /= (roots[i] - roots[j]);
20010  }
20011  }
20012  }
20013  roots[i] -= x;
20014  err[i] = abs(x);
20015  }
20016  }
20017  if( !changed ) {
20018  break;
20019  }
20020  }
20021 
20022  numroots = 0;
20023  bool visited[4] = {false};
20024  for(int i = 0; i < 4; ++i) {
20025  if( !visited[i] ) {
20026  // might be a multiple root, in which case it will have more error than the other roots
20027  // find any neighboring roots, and take the average
20028  complex<IkReal> newroot=roots[i];
20029  int n = 1;
20030  for(int j = i+1; j < 4; ++j) {
20031  // care about error in real much more than imaginary
20032  if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
20033  newroot += roots[j];
20034  n += 1;
20035  visited[j] = true;
20036  }
20037  }
20038  if( n > 1 ) {
20039  newroot /= n;
20040  }
20041  // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt
20042  if( IKabs(imag(newroot)) < tolsqrt ) {
20043  rawroots[numroots++] = real(newroot);
20044  }
20045  }
20046  }
20047 }
20048 };
20049 
20050 
20053 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
20054 IKSolver solver;
20055 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
20056 }
20057 
20058 IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions, void* /* unused */) {
20059 IKSolver solver;
20060 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
20061 }
20062 
20063 IKFAST_API const char* GetKinematicsHash() { return "<robot:GenericRobot - prbt (11ad975bd60aa3f28e8d228465d0f213)>"; }
20064 
20065 IKFAST_API const char* GetIkFastVersion() { return "0x1000004a"; }
20066 
20067 #ifdef IKFAST_NAMESPACE
20068 } // end namespace
20069 #endif
20070 
20071 #ifndef IKFAST_NO_MAIN
20072 #include <stdio.h>
20073 #include <stdlib.h>
20074 #ifdef IKFAST_NAMESPACE
20075 using namespace IKFAST_NAMESPACE;
20076 #endif
20077 int main(int argc, char** argv)
20078 {
20079  if( argc != 12+GetNumFreeParameters()+1 ) {
20080  printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
20081  "Returns the ik solutions given the transformation of the end effector specified by\n"
20082  "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
20083  "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
20084  return 1;
20085  }
20086 
20087  IkSolutionList<IkReal> solutions;
20088  std::vector<IkReal> vfree(GetNumFreeParameters());
20089  IkReal eerot[9],eetrans[3];
20090  eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
20091  eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
20092  eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
20093  for(std::size_t i = 0; i < vfree.size(); ++i)
20094  vfree[i] = atof(argv[13+i]);
20095  bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : nullptr, solutions);
20096 
20097  if( !bSuccess ) {
20098  fprintf(stderr,"Failed to get ik solution\n");
20099  return -1;
20100  }
20101 
20102  printf("Found %d ik solutions:\n", static_cast<int>(solutions.GetNumSolutions()));
20103  std::vector<IkReal> solvalues(GetNumJoints());
20104  for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
20105  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
20106  printf("sol%d (free=%d): ", static_cast<int>(i), static_cast<int>(sol.GetFree().size()));
20107  std::vector<IkReal> vsolfree(sol.GetFree().size());
20108  sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:nullptr);
20109  for( std::size_t j = 0; j < solvalues.size(); ++j)
20110  printf("%.15f, ", solvalues[j]);
20111  printf("\n");
20112  }
20113  return 0;
20114 }
20115 
20116 #endif
void rotationfunction0(IkSolutionListBase< IkReal > &solutions)
static void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int &numroots)
static void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int &numroots)
bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *, IkSolutionListBase< IkReal > &solutions)
The discrete solutions are returned in this structure.
Definition: ikfast.h:73
virtual const std::vector< int > & GetFree() const =0
Gets the indices of the configuration space that have to be preset before a full solution can be retu...
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
manages all the solutions
Definition: ikfast.h:103
virtual size_t GetNumSolutions() const =0
returns the number of solutions stored
virtual void Clear()=0
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
virtual size_t AddSolution(const std::vector< IkSingleDOFSolutionBase< T > > &vinfos, const std::vector< int > &vfree)=0
add one solution and return its index for later retrieval
Default implementation of IkSolutionListBase.
Definition: ikfast.h:276
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:285
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:296
#define IKFAST_VERSION
Header file for all ikfast c++ files/shared objects.
Definition: ikfast.h:45
Definition: ikfast.h:48
x
Definition: pick.py:64
y
Definition: pick.py:65
#define IKFAST_ATAN2_MAGTHRESH
IKFAST_API bool ComputeIk2(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions, void *)
float IKasin(float f)
IKFAST_API int * GetFreeParameters()
float IKatan2Simple(float fy, float fx)
int main(int argc, char **argv)
IKFAST_API int GetNumJoints()
float IKatan2(float fy, float fx)
#define IKFAST_SINCOS_THRESH
IKFAST_API int GetIkRealSize()
float IKacos(float f)
#define IKFAST_EVALCOND_THRESH
float IKsqrt(float f)
float IKsin(float f)
float IKsign(float f)
float IKfmod(float x, float y)
float IKcos(float f)
CheckValue< T > IKPowWithIntegerCheck(T f, int n)
float IKsqr(float f)
IKFAST_API int GetIkType()
CheckValue< T > IKatan2WithCheck(T fy, T fx, T)
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)
float IKtan(float f)
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
#define IKFAST_SOLUTION_THRESH
float IKlog(float f)
IKFAST_API const char * GetIkFastVersion()
IKFAST_API int GetNumFreeParameters()
#define IKFAST_ASSERT(b)
float IKabs(float f)
IKFAST_API const char * GetKinematicsHash()