left_arm_ik.cpp
Go to the documentation of this file.
1 #define IKFAST_HAS_LIBRARY
21 #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
22 using namespace ikfast;
23 
24 // check if the included ikfast version matches what this file was compiled with
25 #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
27 
28 #include <cmath>
29 #include <vector>
30 #include <limits>
31 #include <algorithm>
32 #include <complex>
33 
34 #define IKFAST_STRINGIZE2(s) #s
35 #define IKFAST_STRINGIZE(s) IKFAST_STRINGIZE2(s)
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 #endif // _MSC_VER
71 
72 // lapack routines
73 extern "C" {
74  void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
75  void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
76  void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
77  void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
78  void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info);
79  void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info);
80 }
81 
82 using namespace std; // necessary to get std math routines
83 
84 #ifdef IKFAST_NAMESPACE
85 namespace IKFAST_NAMESPACE {
86 #endif
87 
88 inline float IKabs(float f) { return fabsf(f); }
89 inline double IKabs(double f) { return fabs(f); }
90 
91 inline float IKsqr(float f) { return f*f; }
92 inline double IKsqr(double f) { return f*f; }
93 
94 inline float IKlog(float f) { return logf(f); }
95 inline double IKlog(double f) { return log(f); }
96 
97 // allows asin and acos to exceed 1
98 #ifndef IKFAST_SINCOS_THRESH
99 #define IKFAST_SINCOS_THRESH ((IkReal)0.000001)
100 #endif
101 
102 // used to check input to atan2 for degenerate cases
103 #ifndef IKFAST_ATAN2_MAGTHRESH
104 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)2e-6)
105 #endif
106 
107 // minimum distance of separate solutions
108 #ifndef IKFAST_SOLUTION_THRESH
109 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
110 #endif
111 
112 inline float IKasin(float f)
113 {
114 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
115 if( f <= -1 ) return float(-IKPI_2);
116 else if( f >= 1 ) return float(IKPI_2);
117 return asinf(f);
118 }
119 inline double IKasin(double f)
120 {
121 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
122 if( f <= -1 ) return -IKPI_2;
123 else if( f >= 1 ) return IKPI_2;
124 return asin(f);
125 }
126 
127 // return positive value in [0,y)
128 inline float IKfmod(float x, float y)
129 {
130  while(x < 0) {
131  x += y;
132  }
133  return fmodf(x,y);
134 }
135 
136 // return positive value in [0,y)
137 inline double IKfmod(double x, double y)
138 {
139  while(x < 0) {
140  x += y;
141  }
142  return fmod(x,y);
143 }
144 
145 inline float IKacos(float f)
146 {
147 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
148 if( f <= -1 ) return float(IKPI);
149 else if( f >= 1 ) return float(0);
150 return acosf(f);
151 }
152 inline double IKacos(double f)
153 {
154 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
155 if( f <= -1 ) return IKPI;
156 else if( f >= 1 ) return 0;
157 return acos(f);
158 }
159 inline float IKsin(float f) { return sinf(f); }
160 inline double IKsin(double f) { return sin(f); }
161 inline float IKcos(float f) { return cosf(f); }
162 inline double IKcos(double f) { return cos(f); }
163 inline float IKtan(float f) { return tanf(f); }
164 inline double IKtan(double f) { return tan(f); }
165 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
166 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
167 inline float IKatan2(float fy, float fx) {
168  if( isnan(fy) ) {
169  IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
170  return float(IKPI_2);
171  }
172  else if( isnan(fx) ) {
173  return 0;
174  }
175  return atan2f(fy,fx);
176 }
177 inline double IKatan2(double fy, double fx) {
178  if( isnan(fy) ) {
179  IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
180  return IKPI_2;
181  }
182  else if( isnan(fx) ) {
183  return 0;
184  }
185  return atan2(fy,fx);
186 }
187 
188 inline float IKsign(float f) {
189  if( f > 0 ) {
190  return float(1);
191  }
192  else if( f < 0 ) {
193  return float(-1);
194  }
195  return 0;
196 }
197 
198 inline double IKsign(double f) {
199  if( f > 0 ) {
200  return 1.0;
201  }
202  else if( f < 0 ) {
203  return -1.0;
204  }
205  return 0;
206 }
207 
210 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
211 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,x47,x48,x49,x50,x51,x52,x53,x54,x55,x56,x57,x58,x59,x60,x61,x62,x63,x64,x65,x66,x67,x68,x69,x70,x71,x72,x73,x74,x75,x76,x77,x78,x79;
212 x0=IKcos(j[0]);
213 x1=IKcos(j[1]);
214 x2=IKsin(j[2]);
215 x3=IKcos(j[2]);
216 x4=IKsin(j[1]);
217 x5=IKsin(j[3]);
218 x6=IKcos(j[3]);
219 x7=IKsin(j[0]);
220 x8=IKcos(j[4]);
221 x9=IKsin(j[4]);
222 x10=IKcos(j[5]);
223 x11=IKsin(j[5]);
224 x12=((IkReal(0.258820826967441))*(x9));
225 x13=((IkReal(0.258820826967441))*(x11));
226 x14=((IkReal(1.00000000000000))*(x8));
227 x15=((IkReal(0.0300000000000000))*(x0));
228 x16=((IkReal(1.00000000000000))*(x5));
229 x17=((IkReal(0.965925348838040))*(x11));
230 x18=((IkReal(0.258820826967441))*(x8));
231 x19=((IkReal(0.0470000000000000))*(x0));
232 x20=((IkReal(0.965925348838040))*(x9));
233 x21=((IkReal(1.00000000000000))*(x9));
234 x22=((IkReal(0.00776462480902323))*(x7));
235 x23=((IkReal(0.965925348838040))*(x8));
236 x24=((IkReal(0.0289777604651412))*(x7));
237 x25=((IkReal(1.00000000000000))*(x7));
238 x26=((IkReal(0.235000000000000))*(x0));
239 x27=((IkReal(0.0470000000000000))*(x7));
240 x28=((IkReal(0.0900000000000000))*(x6));
241 x29=((IkReal(0.965925348838040))*(x10));
242 x30=((IkReal(1.00000000000000))*(x0));
243 x31=((IkReal(0.258820826967441))*(x10));
244 x32=((IkReal(0.0900000000000000))*(x0));
245 x33=((IkReal(0.0900000000000000))*(x7));
246 x34=((IkReal(1.00000000000000))*(x6));
247 x35=((x1)*(x3));
248 x36=((x6)*(x9));
249 x37=((x2)*(x4));
250 x38=((x4)*(x7));
251 x39=((IkReal(-0.0470000000000000))*(x6));
252 x40=((x3)*(x4));
253 x41=((x0)*(x5));
254 x42=((x1)*(x2));
255 x43=((x16)*(x7));
256 x44=((x25)*(x6));
257 x45=((x30)*(x37));
258 x46=((x25)*(x37));
259 x47=((((IkReal(-1.00000000000000))*(x35)))+(x37));
260 x48=((((IkReal(0.0470000000000000))*(x35)))+(((IkReal(-0.0470000000000000))*(x37))));
261 x49=((((IkReal(0.0900000000000000))*(x37)))+(((IkReal(-0.0900000000000000))*(x35))));
262 x50=((((IkReal(1.00000000000000))*(x42)))+(((IkReal(1.00000000000000))*(x40))));
263 x51=((IkReal(-1.00000000000000))*(x50));
264 x52=((((IkReal(0.0470000000000000))*(x40)))+(((IkReal(0.0470000000000000))*(x42))));
265 x53=((((IkReal(0.0900000000000000))*(x42)))+(((IkReal(0.0900000000000000))*(x40))));
266 x54=((((IkReal(-1.00000000000000))*(x45)))+(((x0)*(x35))));
267 x55=((((IkReal(-1.00000000000000))*(x46)))+(((x35)*(x7))));
268 x56=((x52)*(x6));
269 x57=((x5)*(x51));
270 x58=((x51)*(x6));
271 x59=((((IkReal(-1.00000000000000))*(x30)*(x35)))+(x45));
272 x60=((((IkReal(-1.00000000000000))*(x25)*(x35)))+(x46));
273 x61=((x30)*(((((IkReal(-1.00000000000000))*(x40)))+(((IkReal(-1.00000000000000))*(x42))))));
274 x62=((x25)*(((((IkReal(-1.00000000000000))*(x40)))+(((IkReal(-1.00000000000000))*(x42))))));
275 x63=((x27)*(((x42)+(x40))));
276 x64=((x33)*(((((IkReal(-1.00000000000000))*(x40)))+(((IkReal(-1.00000000000000))*(x42))))));
277 x65=((x55)*(x6));
278 x66=((x54)*(x6));
279 x67=((x10)*(x5)*(x50));
280 x68=((x5)*(x59));
281 x69=((x41)+(x65));
282 x70=((((x0)*(x6)))+(((x5)*(x60))));
283 x71=((((IkReal(-1.00000000000000))*(x28)*(x55)))+(((IkReal(-1.00000000000000))*(x32)*(x5))));
284 x72=((((IkReal(-1.00000000000000))*(x16)*(x60)))+(((IkReal(-1.00000000000000))*(x30)*(x6))));
285 x73=((((x39)*(x55)))+(((IkReal(-0.0470000000000000))*(x41))));
286 x74=((x73)*(x8));
287 x75=((((IkReal(-1.00000000000000))*(x14)*(x47)))+(((IkReal(-1.00000000000000))*(x21)*(x50)*(x6))));
288 x76=((x11)*(x75));
289 x77=((((x21)*(((((IkReal(-1.00000000000000))*(x43)))+(((x34)*(x54)))))))+(((IkReal(-1.00000000000000))*(x14)*(x61))));
290 x78=((((x21)*(((((x0)*(x16)))+(((x34)*(x55)))))))+(((IkReal(-1.00000000000000))*(x14)*(x62))));
291 x79=((x10)*(x78));
292 eerot[0]=((((x8)*(((((IkReal(-1.00000000000000))*(x43)))+(x66)))))+(((x61)*(x9))));
293 eerot[1]=((((x10)*(((((IkReal(-1.00000000000000))*(x44)))+(x68)))))+(((x11)*(x77))));
294 eerot[2]=((((x10)*(x77)))+(((x11)*(((x44)+(((IkReal(-1.00000000000000))*(x16)*(x59))))))));
295 IkReal x80=((IkReal(1.00000000000000))*(x42));
296 IkReal x81=((IkReal(1.00000000000000))*(x40));
297 eetrans[0]=((((x9)*(((((IkReal(-1.00000000000000))*(x28)*(x54)))+(((x33)*(x5)))))))+(((x15)*(x37)))+(((x8)*(((((IkReal(-1.00000000000000))*(x32)*(x80)))+(((IkReal(-1.00000000000000))*(x32)*(x81)))))))+(((x9)*(((((x19)*(x42)))+(((x19)*(x40)))))))+(((IkReal(-0.250000000000000))*(x0)*(x4)))+(((IkReal(-1.00000000000000))*(x26)*(x80)))+(((IkReal(-1.00000000000000))*(x26)*(x81)))+(((x8)*(((((x39)*(x54)))+(((x27)*(x5)))))))+(((IkReal(-0.0950000000000000))*(x7)))+(((IkReal(-1.00000000000000))*(x15)*(x35))));
298 eerot[3]=((((x23)*(x69)))+(((x20)*(x62)))+(((x18)*(x58)))+(((x12)*(x47))));
299 eerot[4]=((((x17)*(x78)))+(((x29)*(x70)))+(((x13)*(x75)))+(((x31)*(x5)*(x50))));
300 eerot[5]=((((x13)*(x57)))+(((x17)*(x72)))+(((x29)*(x78)))+(((x31)*(x75))));
301 eetrans[1]=((IkReal(0.145000000000000))+(((IkReal(-0.0608228943373486))*(x35)))+(((IkReal(-0.226992456976939))*(x3)*(x38)))+(((x23)*(x64)))+(((IkReal(0.0917629081396138))*(x0)))+(((x20)*(x63)))+(((x12)*(x53)*(x6)))+(((x23)*(x73)))+(((x18)*(x56)))+(((x18)*(x49)))+(((IkReal(-0.226992456976939))*(x42)*(x7)))+(((IkReal(-0.241481337209510))*(x38)))+(((x20)*(x71)))+(((IkReal(-0.0647052067418602))*(x1)))+(((x12)*(x48)))+(((IkReal(-1.00000000000000))*(x24)*(x35)))+(((IkReal(0.0608228943373486))*(x37)))+(((x24)*(x37)))+(((IkReal(0.00776462480902323))*(x42)))+(((IkReal(0.00776462480902323))*(x40))));
302 eerot[6]=((((x20)*(x47)))+(((IkReal(-1.00000000000000))*(x18)*(x69)))+(((IkReal(-1.00000000000000))*(x12)*(x62)))+(((x23)*(x58))));
303 eerot[7]=((((x17)*(x75)))+(((x29)*(x5)*(x50)))+(((IkReal(-1.00000000000000))*(x31)*(x70)))+(((IkReal(-1.00000000000000))*(x13)*(x78))));
304 eerot[8]=((((x17)*(x57)))+(((x29)*(x75)))+(((IkReal(-1.00000000000000))*(x31)*(x78)))+(((IkReal(-1.00000000000000))*(x13)*(x72))));
305 IkReal x82=((IkReal(1.00000000000000))*(x12));
306 IkReal x83=((IkReal(1.00000000000000))*(x18));
307 eetrans[2]=((IkReal(0.370300000000000))+(((x20)*(x48)))+(((IkReal(-0.226992456976939))*(x35)))+(((IkReal(-1.00000000000000))*(x73)*(x83)))+(((x20)*(x53)*(x6)))+(((IkReal(-1.00000000000000))*(x71)*(x82)))+(((IkReal(-1.00000000000000))*(x63)*(x82)))+(((IkReal(0.0289777604651412))*(x42)))+(((IkReal(0.0289777604651412))*(x40)))+(((x23)*(x49)))+(((IkReal(0.226992456976939))*(x37)))+(((IkReal(0.0647052067418602))*(x38)))+(((x22)*(x35)))+(((IkReal(-1.00000000000000))*(x22)*(x37)))+(((IkReal(-0.0245879785619069))*(x0)))+(((IkReal(-0.241481337209510))*(x1)))+(((IkReal(0.0608228943373486))*(x42)*(x7)))+(((IkReal(0.0608228943373486))*(x3)*(x38)))+(((IkReal(-1.00000000000000))*(x64)*(x83)))+(((x23)*(x56))));
308 }
309 
310 IKFAST_API int GetNumFreeParameters() { return 0; }
311 IKFAST_API int* GetFreeParameters() { return NULL; }
312 IKFAST_API int GetNumJoints() { return 6; }
313 
314 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
315 
316 IKFAST_API int GetIkType() { return 0x67000001; }
317 
318 class IKSolver {
319 public:
320 IkReal j3,cj3,sj3,htj3,j4,cj4,sj4,htj4,j5,cj5,sj5,htj5,j6,cj6,sj6,htj6,j7,cj7,sj7,htj7,j8,cj8,sj8,htj8,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;
321 unsigned char _ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5,_ij6[2], _nj6,_ij7[2], _nj7,_ij8[2], _nj8;
322 
323 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
324 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; j6=numeric_limits<IkReal>::quiet_NaN(); _ij6[0] = -1; _ij6[1] = -1; _nj6 = -1; j7=numeric_limits<IkReal>::quiet_NaN(); _ij7[0] = -1; _ij7[1] = -1; _nj7 = -1; j8=numeric_limits<IkReal>::quiet_NaN(); _ij8[0] = -1; _ij8[1] = -1; _nj8 = -1;
325 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
326  solutions.Clear();
327 r00 = eerot[0*3+0];
328 r01 = eerot[0*3+1];
329 r02 = eerot[0*3+2];
330 r10 = eerot[1*3+0];
331 r11 = eerot[1*3+1];
332 r12 = eerot[1*3+2];
333 r20 = eerot[2*3+0];
334 r21 = eerot[2*3+1];
335 r22 = eerot[2*3+2];
336 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
337 
338 new_r00=((IkReal(-1.00000000000000))*(r02));
339 new_r01=r01;
340 new_r02=r00;
341 new_px=((px)+(((IkReal(0.0470000000000000))*(r00))));
342 new_r10=((((IkReal(-0.965925348838040))*(r12)))+(((IkReal(0.258820826967441))*(r22))));
343 new_r11=((((IkReal(0.965925348838040))*(r11)))+(((IkReal(-0.258820826967441))*(r21))));
344 new_r12=((((IkReal(0.965925348838040))*(r10)))+(((IkReal(-0.258820826967441))*(r20))));
345 new_py=((IkReal(-0.0442178233554725))+(((IkReal(0.965925348838040))*(py)))+(((IkReal(0.0453984913953879))*(r10)))+(((IkReal(-0.0121645788674697))*(r20)))+(((IkReal(-0.258820826967441))*(pz))));
346 new_r20=((((IkReal(-0.258820826967441))*(r12)))+(((IkReal(-0.965925348838040))*(r22))));
347 new_r21=((((IkReal(0.965925348838040))*(r21)))+(((IkReal(0.258820826967441))*(r11))));
348 new_r22=((((IkReal(0.965925348838040))*(r20)))+(((IkReal(0.258820826967441))*(r10))));
349 new_pz=((IkReal(-0.395211176585005))+(((IkReal(0.965925348838040))*(pz)))+(((IkReal(0.258820826967441))*(py)))+(((IkReal(0.0121645788674697))*(r10)))+(((IkReal(0.0453984913953879))*(r20))));
350 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;
351 pp=(((px)*(px))+((py)*(py))+((pz)*(pz)));
352 npx=((((px)*(r00)))+(((py)*(r10)))+(((pz)*(r20))));
353 npy=((((px)*(r01)))+(((py)*(r11)))+(((pz)*(r21))));
354 npz=((((px)*(r02)))+(((py)*(r12)))+(((pz)*(r22))));
355 rxp0_0=((((IkReal(-1.00000000000000))*(py)*(r20)))+(((pz)*(r10))));
356 rxp0_1=((((px)*(r20)))+(((IkReal(-1.00000000000000))*(pz)*(r00))));
357 rxp0_2=((((IkReal(-1.00000000000000))*(px)*(r10)))+(((py)*(r00))));
358 rxp1_0=((((IkReal(-1.00000000000000))*(py)*(r21)))+(((pz)*(r11))));
359 rxp1_1=((((px)*(r21)))+(((IkReal(-1.00000000000000))*(pz)*(r01))));
360 rxp1_2=((((IkReal(-1.00000000000000))*(px)*(r11)))+(((py)*(r01))));
361 rxp2_0=((((IkReal(-1.00000000000000))*(py)*(r22)))+(((pz)*(r12))));
362 rxp2_1=((((px)*(r22)))+(((IkReal(-1.00000000000000))*(pz)*(r02))));
363 rxp2_2=((((IkReal(-1.00000000000000))*(px)*(r12)))+(((py)*(r02))));
364 IkReal op[72], zeror[48];
365 int numroots;
366 IkReal x84=((IkReal(0.650000000000000))*(npx));
367 IkReal x85=((IkReal(0.0600000000000000))*(npz));
368 IkReal x86=((IkReal(1.00000000000000))*(pp));
369 IkReal x87=((IkReal(0.0600000000000000))*(npy));
370 IkReal x88=((IkReal(0.0950000000000000))*(r22));
371 IkReal x89=((IkReal(0.120000000000000))*(npx));
372 IkReal x90=((IkReal(1.00000000000000))*(rxp0_2));
373 IkReal x91=((IkReal(2.00000000000000))*(rxp1_2));
374 IkReal x92=((IkReal(0.0950000000000000))*(r21));
375 IkReal x93=((IkReal(0.940000000000000))*(npz));
376 IkReal x94=((IkReal(0.190000000000000))*(r20));
377 IkReal x95=((IkReal(2.00000000000000))*(rxp2_2));
378 IkReal x96=((IkReal(0.180000000000000))*(r21));
379 IkReal x97=((IkReal(0.360000000000000))*(r20));
380 IkReal x98=((IkReal(0.380000000000000))*(r21));
381 IkReal x99=((IkReal(0.290000000000000))*(npx));
382 IkReal x100=((IkReal(0.00570000000000000))+(((IkReal(-1.00000000000000))*(x87))));
383 IkReal x101=((rxp0_2)+(((IkReal(-1.00000000000000))*(x88))));
384 IkReal x102=((IkReal(0.580000000000000))*(npy));
385 IkReal x103=((IkReal(-0.00570000000000000))+(((IkReal(-1.00000000000000))*(x87))));
386 IkReal x104=((IkReal(-1.30000000000000))*(npy));
387 IkReal x105=((IkReal(-0.0950000000000000))*(r21));
388 IkReal x106=((IkReal(-0.190000000000000))*(r20));
389 IkReal x107=((IkReal(0.00570000000000000))+(x87));
390 IkReal x108=((IkReal(-0.00570000000000000))+(x87));
391 IkReal x109=((rxp0_2)+(x88));
392 IkReal x110=((IkReal(-2.00000000000000))*(rxp1_2));
393 IkReal x111=((x88)+(((IkReal(-1.00000000000000))*(x90))));
394 IkReal x112=((IkReal(-0.0350000000000000))+(x84));
395 IkReal x113=((IkReal(0.0496000000000000))+(x85));
396 IkReal x114=((((IkReal(-1.00000000000000))*(x90)))+(((IkReal(-1.00000000000000))*(x88))));
397 IkReal x115=((x86)+(x85));
398 IkReal x116=((x89)+(x93));
399 IkReal x117=((x95)+(x96));
400 op[0]=((((IkReal(-1.00000000000000))*(x115)))+(x112));
401 op[1]=x107;
402 op[2]=x104;
403 op[3]=x89;
404 op[4]=((IkReal(-0.0350000000000000))+(((IkReal(-1.00000000000000))*(x115)))+(((IkReal(-1.00000000000000))*(x84))));
405 op[5]=x100;
406 op[6]=x111;
407 op[7]=x105;
408 op[8]=x91;
409 op[9]=x106;
410 op[10]=x109;
411 op[11]=x92;
412 op[12]=x108;
413 op[13]=((x112)+(x85)+(((IkReal(-1.00000000000000))*(x86))));
414 op[14]=x89;
415 op[15]=x104;
416 op[16]=x103;
417 op[17]=((IkReal(-0.0350000000000000))+(x85)+(((IkReal(-1.00000000000000))*(x84)))+(((IkReal(-1.00000000000000))*(x86))));
418 op[18]=x105;
419 op[19]=x114;
420 op[20]=x106;
421 op[21]=x91;
422 op[22]=x92;
423 op[23]=x101;
424 op[24]=((IkReal(-0.0108000000000000))+(x116));
425 op[25]=IkReal(0);
426 op[26]=((IkReal(-0.240000000000000))*(npy));
427 op[27]=IkReal(0);
428 op[28]=((IkReal(-0.0108000000000000))+(x93)+(((IkReal(-1.00000000000000))*(x89))));
429 op[29]=IkReal(0);
430 op[30]=((x96)+(((IkReal(-1.00000000000000))*(x94)))+(((IkReal(-1.00000000000000))*(x95))));
431 op[31]=IkReal(0);
432 op[32]=((x98)+(x97));
433 op[33]=IkReal(0);
434 op[34]=((((IkReal(-1.00000000000000))*(x117)))+(x94));
435 op[35]=IkReal(0);
436 op[36]=IkReal(0);
437 op[37]=((IkReal(0.0108000000000000))+(x93)+(((IkReal(-1.00000000000000))*(x89))));
438 op[38]=IkReal(0);
439 op[39]=((IkReal(0.240000000000000))*(npy));
440 op[40]=IkReal(0);
441 op[41]=((IkReal(0.0108000000000000))+(x116));
442 op[42]=IkReal(0);
443 op[43]=((x94)+(x96)+(((IkReal(-1.00000000000000))*(x95))));
444 op[44]=IkReal(0);
445 op[45]=((x97)+(((IkReal(-1.00000000000000))*(x98))));
446 op[46]=IkReal(0);
447 op[47]=((((IkReal(-1.00000000000000))*(x117)))+(((IkReal(-1.00000000000000))*(x94))));
448 op[48]=((x113)+(((IkReal(-1.00000000000000))*(x99)))+(((IkReal(-1.00000000000000))*(x86))));
449 op[49]=x107;
450 op[50]=x102;
451 op[51]=x89;
452 op[52]=((x113)+(x99)+(((IkReal(-1.00000000000000))*(x86))));
453 op[53]=x100;
454 op[54]=x101;
455 op[55]=x105;
456 op[56]=x110;
457 op[57]=x106;
458 op[58]=x114;
459 op[59]=x92;
460 op[60]=x108;
461 op[61]=((IkReal(0.0496000000000000))+(((IkReal(-1.00000000000000))*(x115)))+(((IkReal(-1.00000000000000))*(x99))));
462 op[62]=x89;
463 op[63]=x102;
464 op[64]=x103;
465 op[65]=((IkReal(0.0496000000000000))+(((IkReal(-1.00000000000000))*(x115)))+(x99));
466 op[66]=x105;
467 op[67]=x109;
468 op[68]=x106;
469 op[69]=x110;
470 op[70]=x92;
471 op[71]=x111;
472 solvedialyticpoly8qep(op,zeror,numroots);
473 IkReal j7array[16], cj7array[16], sj7array[16], j8array[16], cj8array[16], sj8array[16], j6array[16], cj6array[16], sj6array[16];
474 int numsolutions = 0;
475 for(int ij7 = 0; ij7 < numroots; ij7 += 3)
476 {
477 IkReal htj7 = zeror[ij7+0], htj8 = zeror[ij7+1], htj6 = zeror[ij7+2];
478 j7array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj7)));
479 j8array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj8)));
480 j6array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj6)));
481 IkReal x118=(htj7)*(htj7);
482 IkReal x119=(htj8)*(htj8);
483 IkReal x120=(htj6)*(htj6);
484 cj7array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x118))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x118)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x118))))));
485 cj8array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x119))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x119)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x119))))));
486 cj6array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x120))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x120)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x120))))));
487 sj7array[numsolutions]=((IkReal(2.00000000000000))*(htj7)*(((IKabs(((IkReal(1.00000000000000))+((htj7)*(htj7)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj7)*(htj7))))):(IkReal)1.0e30)));
488 sj8array[numsolutions]=((IkReal(2.00000000000000))*(htj8)*(((IKabs(((IkReal(1.00000000000000))+((htj8)*(htj8)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj8)*(htj8))))):(IkReal)1.0e30)));
489 sj6array[numsolutions]=((IkReal(2.00000000000000))*(htj6)*(((IKabs(((IkReal(1.00000000000000))+((htj6)*(htj6)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj6)*(htj6))))):(IkReal)1.0e30)));
490 if( j7array[numsolutions] > IKPI )
491 {
492  j7array[numsolutions]-=IK2PI;
493 }
494 else if( j7array[numsolutions] < -IKPI )
495 {
496  j7array[numsolutions]+=IK2PI;
497 }
498 if( j8array[numsolutions] > IKPI )
499 {
500  j8array[numsolutions]-=IK2PI;
501 }
502 else if( j8array[numsolutions] < -IKPI )
503 {
504  j8array[numsolutions]+=IK2PI;
505 }
506 if( j6array[numsolutions] > IKPI )
507 {
508  j6array[numsolutions]-=IK2PI;
509 }
510 else if( j6array[numsolutions] < -IKPI )
511 {
512  j6array[numsolutions]+=IK2PI;
513 }
514 numsolutions++;
515 }
516 bool j7valid[16]={true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true};
517 _nj7 = 16;
518 _nj8 = 1;
519 _nj6 = 1;
520 for(int ij7 = 0; ij7 < numsolutions; ++ij7)
521  {
522 if( !j7valid[ij7] )
523 {
524  continue;
525 }
526 _ij7[0] = ij7; _ij7[1] = -1;
527 _ij8[0] = 0; _ij8[1] = -1;
528 _ij6[0] = 0; _ij6[1] = -1;
529 for(int iij7 = ij7+1; iij7 < numsolutions; ++iij7)
530 {
531 if( !j7valid[iij7] ) { continue; }
532 if( IKabs(cj7array[ij7]-cj7array[iij7]) < IKFAST_SOLUTION_THRESH && IKabs(sj7array[ij7]-sj7array[iij7]) < IKFAST_SOLUTION_THRESH && IKabs(cj8array[ij7]-cj8array[iij7]) < IKFAST_SOLUTION_THRESH && IKabs(sj8array[ij7]-sj8array[iij7]) < IKFAST_SOLUTION_THRESH && IKabs(cj6array[ij7]-cj6array[iij7]) < IKFAST_SOLUTION_THRESH && IKabs(sj6array[ij7]-sj6array[iij7]) < IKFAST_SOLUTION_THRESH && 1 )
533 {
534  j7valid[iij7]=false; _ij7[1] = iij7; _ij8[1] = 0; _ij6[1] = 0; break;
535 }
536 }
537  j7 = j7array[ij7]; cj7 = cj7array[ij7]; sj7 = sj7array[ij7];
538 
539  j8 = j8array[ij7]; cj8 = cj8array[ij7]; sj8 = sj8array[ij7];
540 
541  j6 = j6array[ij7]; cj6 = cj6array[ij7]; sj6 = sj6array[ij7];
542 
543 {
544 IkReal dummyeval[1];
545 IkReal gconst0;
546 IkReal x121=(sj8)*(sj8);
547 IkReal x122=(cj8)*(cj8);
548 IkReal x123=((r00)*(r11));
549 IkReal x124=((r02)*(sj7));
550 IkReal x125=((cj7)*(x122));
551 IkReal x126=((IkReal(1.00000000000000))*(r12)*(sj7));
552 IkReal x127=((IkReal(1.00000000000000))*(r01)*(r10));
553 IkReal x128=((cj7)*(x121));
554 gconst0=IKsign(((((IkReal(-1.00000000000000))*(r00)*(sj8)*(x126)))+(((r10)*(sj8)*(x124)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x126)))+(((x123)*(x125)))+(((x123)*(x128)))+(((IkReal(-1.00000000000000))*(x125)*(x127)))+(((cj8)*(r11)*(x124)))+(((IkReal(-1.00000000000000))*(x127)*(x128)))));
555 IkReal x129=(sj8)*(sj8);
556 IkReal x130=(cj8)*(cj8);
557 IkReal x131=((r00)*(r11));
558 IkReal x132=((r02)*(sj7));
559 IkReal x133=((cj7)*(x130));
560 IkReal x134=((IkReal(1.00000000000000))*(r12)*(sj7));
561 IkReal x135=((IkReal(1.00000000000000))*(r01)*(r10));
562 IkReal x136=((cj7)*(x129));
563 dummyeval[0]=((((IkReal(-1.00000000000000))*(x135)*(x136)))+(((r10)*(sj8)*(x132)))+(((IkReal(-1.00000000000000))*(x133)*(x135)))+(((x131)*(x133)))+(((x131)*(x136)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x134)))+(((cj8)*(r11)*(x132)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x134))));
564 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
565 {
566 {
567 IkReal dummyeval[1];
568 IkReal gconst1;
569 IkReal x137=(sj8)*(sj8);
570 IkReal x138=(cj8)*(cj8);
571 IkReal x139=((IkReal(1.00000000000000))*(r10));
572 IkReal x140=((cj7)*(sj8));
573 IkReal x141=((r00)*(r11));
574 IkReal x142=((cj7)*(cj8));
575 IkReal x143=((sj7)*(x137));
576 IkReal x144=((sj7)*(x138));
577 gconst1=IKsign(((((r01)*(r12)*(x142)))+(((IkReal(-1.00000000000000))*(r02)*(x139)*(x140)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x142)))+(((x141)*(x144)))+(((x141)*(x143)))+(((r00)*(r12)*(x140)))+(((IkReal(-1.00000000000000))*(r01)*(x139)*(x143)))+(((IkReal(-1.00000000000000))*(r01)*(x139)*(x144)))));
578 IkReal x145=(sj8)*(sj8);
579 IkReal x146=(cj8)*(cj8);
580 IkReal x147=((IkReal(1.00000000000000))*(r10));
581 IkReal x148=((cj7)*(sj8));
582 IkReal x149=((r00)*(r11));
583 IkReal x150=((cj7)*(cj8));
584 IkReal x151=((sj7)*(x145));
585 IkReal x152=((sj7)*(x146));
586 dummyeval[0]=((((x149)*(x152)))+(((x149)*(x151)))+(((IkReal(-1.00000000000000))*(r02)*(x147)*(x148)))+(((IkReal(-1.00000000000000))*(r01)*(x147)*(x152)))+(((IkReal(-1.00000000000000))*(r01)*(x147)*(x151)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x150)))+(((r00)*(r12)*(x148)))+(((r01)*(r12)*(x150))));
587 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
588 {
589 {
590 IkReal dummyeval[1];
591 dummyeval[0]=sj6;
592 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
593 {
594 {
595 IkReal evalcond[3];
596 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
597 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
598 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
599 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 )
600 {
601 {
602 IkReal j5array[1], cj5array[1], sj5array[1];
603 bool j5valid[1]={false};
604 _nj5 = 1;
605 IkReal x153=((IkReal(4.00000000000000))*(sj7));
606 IkReal x154=((npy)*(sj8));
607 IkReal x155=((IkReal(4.00000000000000))*(cj7));
608 IkReal x156=((cj8)*(npx));
609 if( IKabs(((IkReal(0.120000000000000))+(((x153)*(x154)))+(((IkReal(0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x153)*(x156)))+(((npz)*(x155))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x154)*(x155)))+(((x155)*(x156)))+(((npz)*(x153)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((x153)*(x154)))+(((IkReal(0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x153)*(x156)))+(((npz)*(x155)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x154)*(x155)))+(((x155)*(x156)))+(((npz)*(x153)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
610  continue;
611 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((x153)*(x154)))+(((IkReal(0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x153)*(x156)))+(((npz)*(x155)))), ((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x154)*(x155)))+(((x155)*(x156)))+(((npz)*(x153)))+(((IkReal(-0.360000000000000))*(cj7)))));
612 sj5array[0]=IKsin(j5array[0]);
613 cj5array[0]=IKcos(j5array[0]);
614 if( j5array[0] > IKPI )
615 {
616  j5array[0]-=IK2PI;
617 }
618 else if( j5array[0] < -IKPI )
619 { j5array[0]+=IK2PI;
620 }
621 j5valid[0] = true;
622 for(int ij5 = 0; ij5 < 1; ++ij5)
623 {
624 if( !j5valid[ij5] )
625 {
626  continue;
627 }
628 _ij5[0] = ij5; _ij5[1] = -1;
629 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
630 {
631 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
632 {
633  j5valid[iij5]=false; _ij5[1] = iij5; break;
634 }
635 }
636 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
637 {
638 IkReal evalcond[2];
639 IkReal x157=((IkReal(1.00000000000000))*(sj7));
640 IkReal x158=((npy)*(sj8));
641 IkReal x159=((cj8)*(npx));
642 evalcond[0]=((IkReal(0.235000000000000))+(((cj7)*(x158)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x157)))+(((IkReal(-1.00000000000000))*(cj7)*(x159)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
643 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x157)*(x159)))+(((sj7)*(x158)))+(((IkReal(-0.250000000000000))*(IKsin(j5))))+(((cj7)*(npz))));
644 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
645 {
646 continue;
647 }
648 }
649 
650 {
651 IkReal dummyeval[1];
652 IkReal gconst66;
653 IkReal x160=(sj8)*(sj8);
654 IkReal x161=(cj8)*(cj8);
655 IkReal x162=((IkReal(2.00000000000000))*(cj8)*(sj8));
656 gconst66=IKsign(((((x160)*((r00)*(r00))))+(((x161)*((r01)*(r01))))+(((x160)*((r10)*(r10))))+(((x161)*((r11)*(r11))))+(((r10)*(r11)*(x162)))+(((r00)*(r01)*(x162)))));
657 IkReal x163=(sj8)*(sj8);
658 IkReal x164=(cj8)*(cj8);
659 IkReal x165=((IkReal(2.00000000000000))*(cj8)*(sj8));
660 dummyeval[0]=((((x164)*((r01)*(r01))))+(((x163)*((r00)*(r00))))+(((x164)*((r11)*(r11))))+(((x163)*((r10)*(r10))))+(((r10)*(r11)*(x165)))+(((r00)*(r01)*(x165))));
661 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
662 {
663 {
664 IkReal dummyeval[1];
665 IkReal gconst68;
666 gconst68=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
667 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
668 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
669 {
670 {
671 IkReal dummyeval[1];
672 IkReal gconst67;
673 IkReal x166=(sj8)*(sj8);
674 IkReal x167=(cj8)*(cj8);
675 IkReal x168=((r00)*(r11));
676 IkReal x169=((r02)*(sj7));
677 IkReal x170=((cj7)*(x167));
678 IkReal x171=((IkReal(1.00000000000000))*(r12)*(sj7));
679 IkReal x172=((IkReal(1.00000000000000))*(r01)*(r10));
680 IkReal x173=((cj7)*(x166));
681 gconst67=IKsign(((((cj8)*(r11)*(x169)))+(((x168)*(x173)))+(((x168)*(x170)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x171)))+(((IkReal(-1.00000000000000))*(x170)*(x172)))+(((r10)*(sj8)*(x169)))+(((IkReal(-1.00000000000000))*(x172)*(x173)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x171)))));
682 IkReal x174=(sj8)*(sj8);
683 IkReal x175=(cj8)*(cj8);
684 IkReal x176=((r00)*(r11));
685 IkReal x177=((r02)*(sj7));
686 IkReal x178=((cj7)*(x175));
687 IkReal x179=((IkReal(1.00000000000000))*(r12)*(sj7));
688 IkReal x180=((IkReal(1.00000000000000))*(r01)*(r10));
689 IkReal x181=((cj7)*(x174));
690 dummyeval[0]=((((cj8)*(r11)*(x177)))+(((IkReal(-1.00000000000000))*(x178)*(x180)))+(((x176)*(x181)))+(((x176)*(x178)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x179)))+(((IkReal(-1.00000000000000))*(x180)*(x181)))+(((r10)*(sj8)*(x177)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x179))));
691 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
692 {
693 continue;
694 
695 } else
696 {
697 {
698 IkReal j3array[1], cj3array[1], sj3array[1];
699 bool j3valid[1]={false};
700 _nj3 = 1;
701 IkReal x182=((cj7)*(cj8));
702 IkReal x183=((IkReal(1.00000000000000))*(cj7)*(sj8));
703 if( IKabs(((gconst67)*(((((IkReal(-1.00000000000000))*(r11)*(x183)))+(((r12)*(sj7)))+(((r10)*(x182))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst67)*(((((IkReal(-1.00000000000000))*(r01)*(x183)))+(((r00)*(x182)))+(((r02)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH )
704  continue;
705 j3array[0]=IKatan2(((gconst67)*(((((IkReal(-1.00000000000000))*(r11)*(x183)))+(((r12)*(sj7)))+(((r10)*(x182)))))), ((gconst67)*(((((IkReal(-1.00000000000000))*(r01)*(x183)))+(((r00)*(x182)))+(((r02)*(sj7)))))));
706 sj3array[0]=IKsin(j3array[0]);
707 cj3array[0]=IKcos(j3array[0]);
708 if( j3array[0] > IKPI )
709 {
710  j3array[0]-=IK2PI;
711 }
712 else if( j3array[0] < -IKPI )
713 { j3array[0]+=IK2PI;
714 }
715 j3valid[0] = true;
716 for(int ij3 = 0; ij3 < 1; ++ij3)
717 {
718 if( !j3valid[ij3] )
719 {
720  continue;
721 }
722 _ij3[0] = ij3; _ij3[1] = -1;
723 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
724 {
725 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
726 {
727  j3valid[iij3]=false; _ij3[1] = iij3; break;
728 }
729 }
730 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
731 {
732 IkReal evalcond[4];
733 IkReal x184=IKsin(j3);
734 IkReal x185=IKcos(j3);
735 IkReal x186=((IkReal(1.00000000000000))*(sj8));
736 IkReal x187=((IkReal(1.00000000000000))*(cj8));
737 IkReal x188=((r01)*(sj8));
738 IkReal x189=((cj8)*(r10));
739 IkReal x190=((sj7)*(x185));
740 IkReal x191=((cj7)*(x184));
741 IkReal x192=((r00)*(x184));
742 IkReal x193=((sj7)*(x184));
743 IkReal x194=((cj7)*(x185));
744 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x185)*(x186)))+(((sj8)*(x192)))+(((cj8)*(r01)*(x184)))+(((IkReal(-1.00000000000000))*(r11)*(x185)*(x187))));
745 evalcond[1]=((((IkReal(-1.00000000000000))*(r00)*(x185)*(x186)))+(((IkReal(-1.00000000000000))*(r10)*(x184)*(x186)))+(((IkReal(-1.00000000000000))*(r11)*(x184)*(x187)))+(((IkReal(-1.00000000000000))*(r01)*(x185)*(x187))));
746 evalcond[2]=((((x188)*(x191)))+(((x189)*(x194)))+(((r12)*(x190)))+(((IkReal(-1.00000000000000))*(r11)*(x186)*(x194)))+(((IkReal(-1.00000000000000))*(r00)*(x187)*(x191)))+(((IkReal(-1.00000000000000))*(r02)*(x193))));
747 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x194)))+(((x188)*(x193)))+(((x189)*(x190)))+(((IkReal(-1.00000000000000))*(sj7)*(x187)*(x192)))+(((IkReal(-1.00000000000000))*(r11)*(x186)*(x190)))+(((r02)*(x191))));
748 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
749 {
750 continue;
751 }
752 }
753 
754 {
755 IkReal dummyeval[1];
756 IkReal gconst69;
757 gconst69=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
758 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
759 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
760 {
761 {
762 IkReal dummyeval[1];
763 IkReal gconst70;
764 gconst70=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
765 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
766 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
767 {
768 continue;
769 
770 } else
771 {
772 {
773 IkReal j4array[1], cj4array[1], sj4array[1];
774 bool j4valid[1]={false};
775 _nj4 = 1;
776 IkReal x195=((cj3)*(cj5));
777 IkReal x196=((r02)*(sj7));
778 IkReal x197=((cj8)*(r00));
779 IkReal x198=((r22)*(sj7));
780 IkReal x199=((cj5)*(sj3));
781 IkReal x200=((cj7)*(cj8));
782 IkReal x201=((IkReal(1.00000000000000))*(sj5));
783 IkReal x202=((sj3)*(sj5));
784 IkReal x203=((r12)*(sj7));
785 IkReal x204=((cj3)*(cj7)*(sj5));
786 IkReal x205=((IkReal(1.00000000000000))*(cj7)*(sj8));
787 if( IKabs(((gconst70)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x200)*(x201)))+(((IkReal(-1.00000000000000))*(r11)*(x199)*(x205)))+(((x195)*(x196)))+(((IkReal(-1.00000000000000))*(x198)*(x201)))+(((IkReal(-1.00000000000000))*(r01)*(x195)*(x205)))+(((cj7)*(x195)*(x197)))+(((r10)*(x199)*(x200)))+(((x199)*(x203))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst70)*(((((cj5)*(x198)))+(((r10)*(x200)*(x202)))+(((cj3)*(sj5)*(x196)))+(((cj5)*(r20)*(x200)))+(((x197)*(x204)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x201)))+(((x202)*(x203)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x201)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x205))))))) < IKFAST_ATAN2_MAGTHRESH )
788  continue;
789 j4array[0]=IKatan2(((gconst70)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x200)*(x201)))+(((IkReal(-1.00000000000000))*(r11)*(x199)*(x205)))+(((x195)*(x196)))+(((IkReal(-1.00000000000000))*(x198)*(x201)))+(((IkReal(-1.00000000000000))*(r01)*(x195)*(x205)))+(((cj7)*(x195)*(x197)))+(((r10)*(x199)*(x200)))+(((x199)*(x203)))))), ((gconst70)*(((((cj5)*(x198)))+(((r10)*(x200)*(x202)))+(((cj3)*(sj5)*(x196)))+(((cj5)*(r20)*(x200)))+(((x197)*(x204)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x201)))+(((x202)*(x203)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x201)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x205)))))));
790 sj4array[0]=IKsin(j4array[0]);
791 cj4array[0]=IKcos(j4array[0]);
792 if( j4array[0] > IKPI )
793 {
794  j4array[0]-=IK2PI;
795 }
796 else if( j4array[0] < -IKPI )
797 { j4array[0]+=IK2PI;
798 }
799 j4valid[0] = true;
800 for(int ij4 = 0; ij4 < 1; ++ij4)
801 {
802 if( !j4valid[ij4] )
803 {
804  continue;
805 }
806 _ij4[0] = ij4; _ij4[1] = -1;
807 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
808 {
809 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
810 {
811  j4valid[iij4]=false; _ij4[1] = iij4; break;
812 }
813 }
814 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
815 {
816 IkReal evalcond[4];
817 IkReal x206=IKcos(j4);
818 IkReal x207=IKsin(j4);
819 IkReal x208=((IkReal(1.00000000000000))*(cj7));
820 IkReal x209=((cj8)*(r20));
821 IkReal x210=((cj3)*(r02));
822 IkReal x211=((IkReal(1.00000000000000))*(sj7));
823 IkReal x212=((sj3)*(sj7));
824 IkReal x213=((r21)*(sj8));
825 IkReal x214=((cj8)*(r10));
826 IkReal x215=((sj5)*(x206));
827 IkReal x216=((cj5)*(x207));
828 IkReal x217=((r11)*(sj3)*(sj8));
829 IkReal x218=((cj3)*(cj8)*(r00));
830 IkReal x219=((cj5)*(x206));
831 IkReal x220=((cj3)*(r01)*(sj8));
832 IkReal x221=((sj5)*(x207));
833 IkReal x222=((x215)+(x216));
834 evalcond[0]=((((cj7)*(x213)))+(((IkReal(-1.00000000000000))*(r22)*(x211)))+(((IkReal(-1.00000000000000))*(x208)*(x209)))+(x221)+(((IkReal(-1.00000000000000))*(x219))));
835 evalcond[1]=((x222)+(((sj7)*(x213)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x209)*(x211))));
836 evalcond[2]=((((cj7)*(sj3)*(x214)))+(((cj7)*(x218)))+(((r12)*(x212)))+(((IkReal(-1.00000000000000))*(x208)*(x220)))+(x222)+(((sj7)*(x210)))+(((IkReal(-1.00000000000000))*(x208)*(x217))));
837 evalcond[3]=((x219)+(((sj7)*(x218)))+(((x212)*(x214)))+(((IkReal(-1.00000000000000))*(x211)*(x217)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x208)))+(((IkReal(-1.00000000000000))*(x211)*(x220)))+(((IkReal(-1.00000000000000))*(x208)*(x210)))+(((IkReal(-1.00000000000000))*(x221))));
838 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
839 {
840 continue;
841 }
842 }
843 
844 {
845 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
846 vinfos[0].jointtype = 1;
847 vinfos[0].foffset = j3;
848 vinfos[0].indices[0] = _ij3[0];
849 vinfos[0].indices[1] = _ij3[1];
850 vinfos[0].maxsolutions = _nj3;
851 vinfos[1].jointtype = 1;
852 vinfos[1].foffset = j4;
853 vinfos[1].indices[0] = _ij4[0];
854 vinfos[1].indices[1] = _ij4[1];
855 vinfos[1].maxsolutions = _nj4;
856 vinfos[2].jointtype = 1;
857 vinfos[2].foffset = j5;
858 vinfos[2].indices[0] = _ij5[0];
859 vinfos[2].indices[1] = _ij5[1];
860 vinfos[2].maxsolutions = _nj5;
861 vinfos[3].jointtype = 1;
862 vinfos[3].foffset = j6;
863 vinfos[3].indices[0] = _ij6[0];
864 vinfos[3].indices[1] = _ij6[1];
865 vinfos[3].maxsolutions = _nj6;
866 vinfos[4].jointtype = 1;
867 vinfos[4].foffset = j7;
868 vinfos[4].indices[0] = _ij7[0];
869 vinfos[4].indices[1] = _ij7[1];
870 vinfos[4].maxsolutions = _nj7;
871 vinfos[5].jointtype = 1;
872 vinfos[5].foffset = j8;
873 vinfos[5].indices[0] = _ij8[0];
874 vinfos[5].indices[1] = _ij8[1];
875 vinfos[5].maxsolutions = _nj8;
876 std::vector<int> vfree(0);
877 solutions.AddSolution(vinfos,vfree);
878 }
879 }
880 }
881 
882 }
883 
884 }
885 
886 } else
887 {
888 {
889 IkReal j4array[1], cj4array[1], sj4array[1];
890 bool j4valid[1]={false};
891 _nj4 = 1;
892 IkReal x223=((r21)*(sj8));
893 IkReal x224=((sj5)*(sj7));
894 IkReal x225=((cj5)*(sj7));
895 IkReal x226=((cj5)*(cj7));
896 IkReal x227=((cj8)*(r20));
897 IkReal x228=((cj7)*(sj5));
898 if( IKabs(((gconst69)*(((((IkReal(-1.00000000000000))*(r22)*(x224)))+(((x223)*(x225)))+(((x223)*(x228)))+(((IkReal(-1.00000000000000))*(x225)*(x227)))+(((IkReal(-1.00000000000000))*(x227)*(x228)))+(((r22)*(x226))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst69)*(((((x223)*(x224)))+(((x226)*(x227)))+(((IkReal(-1.00000000000000))*(x224)*(x227)))+(((r22)*(x228)))+(((r22)*(x225)))+(((IkReal(-1.00000000000000))*(x223)*(x226))))))) < IKFAST_ATAN2_MAGTHRESH )
899  continue;
900 j4array[0]=IKatan2(((gconst69)*(((((IkReal(-1.00000000000000))*(r22)*(x224)))+(((x223)*(x225)))+(((x223)*(x228)))+(((IkReal(-1.00000000000000))*(x225)*(x227)))+(((IkReal(-1.00000000000000))*(x227)*(x228)))+(((r22)*(x226)))))), ((gconst69)*(((((x223)*(x224)))+(((x226)*(x227)))+(((IkReal(-1.00000000000000))*(x224)*(x227)))+(((r22)*(x228)))+(((r22)*(x225)))+(((IkReal(-1.00000000000000))*(x223)*(x226)))))));
901 sj4array[0]=IKsin(j4array[0]);
902 cj4array[0]=IKcos(j4array[0]);
903 if( j4array[0] > IKPI )
904 {
905  j4array[0]-=IK2PI;
906 }
907 else if( j4array[0] < -IKPI )
908 { j4array[0]+=IK2PI;
909 }
910 j4valid[0] = true;
911 for(int ij4 = 0; ij4 < 1; ++ij4)
912 {
913 if( !j4valid[ij4] )
914 {
915  continue;
916 }
917 _ij4[0] = ij4; _ij4[1] = -1;
918 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
919 {
920 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
921 {
922  j4valid[iij4]=false; _ij4[1] = iij4; break;
923 }
924 }
925 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
926 {
927 IkReal evalcond[4];
928 IkReal x229=IKcos(j4);
929 IkReal x230=IKsin(j4);
930 IkReal x231=((IkReal(1.00000000000000))*(cj7));
931 IkReal x232=((cj8)*(r20));
932 IkReal x233=((cj3)*(r02));
933 IkReal x234=((IkReal(1.00000000000000))*(sj7));
934 IkReal x235=((sj3)*(sj7));
935 IkReal x236=((r21)*(sj8));
936 IkReal x237=((cj8)*(r10));
937 IkReal x238=((sj5)*(x229));
938 IkReal x239=((cj5)*(x230));
939 IkReal x240=((r11)*(sj3)*(sj8));
940 IkReal x241=((cj3)*(cj8)*(r00));
941 IkReal x242=((cj5)*(x229));
942 IkReal x243=((cj3)*(r01)*(sj8));
943 IkReal x244=((sj5)*(x230));
944 IkReal x245=((x238)+(x239));
945 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x234)))+(((IkReal(-1.00000000000000))*(x242)))+(x244)+(((IkReal(-1.00000000000000))*(x231)*(x232)))+(((cj7)*(x236))));
946 evalcond[1]=((x245)+(((IkReal(-1.00000000000000))*(x232)*(x234)))+(((cj7)*(r22)))+(((sj7)*(x236))));
947 evalcond[2]=((((cj7)*(x241)))+(((IkReal(-1.00000000000000))*(x231)*(x243)))+(((IkReal(-1.00000000000000))*(x231)*(x240)))+(x245)+(((cj7)*(sj3)*(x237)))+(((sj7)*(x233)))+(((r12)*(x235))));
948 evalcond[3]=((((IkReal(-1.00000000000000))*(x244)))+(((IkReal(-1.00000000000000))*(x234)*(x240)))+(((IkReal(-1.00000000000000))*(x234)*(x243)))+(x242)+(((x235)*(x237)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x231)))+(((IkReal(-1.00000000000000))*(x231)*(x233)))+(((sj7)*(x241))));
949 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
950 {
951 continue;
952 }
953 }
954 
955 {
956 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
957 vinfos[0].jointtype = 1;
958 vinfos[0].foffset = j3;
959 vinfos[0].indices[0] = _ij3[0];
960 vinfos[0].indices[1] = _ij3[1];
961 vinfos[0].maxsolutions = _nj3;
962 vinfos[1].jointtype = 1;
963 vinfos[1].foffset = j4;
964 vinfos[1].indices[0] = _ij4[0];
965 vinfos[1].indices[1] = _ij4[1];
966 vinfos[1].maxsolutions = _nj4;
967 vinfos[2].jointtype = 1;
968 vinfos[2].foffset = j5;
969 vinfos[2].indices[0] = _ij5[0];
970 vinfos[2].indices[1] = _ij5[1];
971 vinfos[2].maxsolutions = _nj5;
972 vinfos[3].jointtype = 1;
973 vinfos[3].foffset = j6;
974 vinfos[3].indices[0] = _ij6[0];
975 vinfos[3].indices[1] = _ij6[1];
976 vinfos[3].maxsolutions = _nj6;
977 vinfos[4].jointtype = 1;
978 vinfos[4].foffset = j7;
979 vinfos[4].indices[0] = _ij7[0];
980 vinfos[4].indices[1] = _ij7[1];
981 vinfos[4].maxsolutions = _nj7;
982 vinfos[5].jointtype = 1;
983 vinfos[5].foffset = j8;
984 vinfos[5].indices[0] = _ij8[0];
985 vinfos[5].indices[1] = _ij8[1];
986 vinfos[5].maxsolutions = _nj8;
987 std::vector<int> vfree(0);
988 solutions.AddSolution(vinfos,vfree);
989 }
990 }
991 }
992 
993 }
994 
995 }
996 }
997 }
998 
999 }
1000 
1001 }
1002 
1003 } else
1004 {
1005 {
1006 IkReal j4array[1], cj4array[1], sj4array[1];
1007 bool j4valid[1]={false};
1008 _nj4 = 1;
1009 IkReal x246=((sj5)*(sj7));
1010 IkReal x247=((r21)*(sj8));
1011 IkReal x248=((cj5)*(sj7));
1012 IkReal x249=((cj8)*(r20));
1013 IkReal x250=((cj5)*(cj7));
1014 IkReal x251=((cj7)*(sj5));
1015 if( IKabs(((gconst68)*(((((IkReal(-1.00000000000000))*(x249)*(x251)))+(((IkReal(-1.00000000000000))*(x248)*(x249)))+(((r22)*(x250)))+(((x247)*(x248)))+(((IkReal(-1.00000000000000))*(r22)*(x246)))+(((x247)*(x251))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst68)*(((((x249)*(x250)))+(((r22)*(x248)))+(((IkReal(-1.00000000000000))*(x247)*(x250)))+(((IkReal(-1.00000000000000))*(x246)*(x249)))+(((r22)*(x251)))+(((x246)*(x247))))))) < IKFAST_ATAN2_MAGTHRESH )
1016  continue;
1017 j4array[0]=IKatan2(((gconst68)*(((((IkReal(-1.00000000000000))*(x249)*(x251)))+(((IkReal(-1.00000000000000))*(x248)*(x249)))+(((r22)*(x250)))+(((x247)*(x248)))+(((IkReal(-1.00000000000000))*(r22)*(x246)))+(((x247)*(x251)))))), ((gconst68)*(((((x249)*(x250)))+(((r22)*(x248)))+(((IkReal(-1.00000000000000))*(x247)*(x250)))+(((IkReal(-1.00000000000000))*(x246)*(x249)))+(((r22)*(x251)))+(((x246)*(x247)))))));
1018 sj4array[0]=IKsin(j4array[0]);
1019 cj4array[0]=IKcos(j4array[0]);
1020 if( j4array[0] > IKPI )
1021 {
1022  j4array[0]-=IK2PI;
1023 }
1024 else if( j4array[0] < -IKPI )
1025 { j4array[0]+=IK2PI;
1026 }
1027 j4valid[0] = true;
1028 for(int ij4 = 0; ij4 < 1; ++ij4)
1029 {
1030 if( !j4valid[ij4] )
1031 {
1032  continue;
1033 }
1034 _ij4[0] = ij4; _ij4[1] = -1;
1035 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1036 {
1037 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1038 {
1039  j4valid[iij4]=false; _ij4[1] = iij4; break;
1040 }
1041 }
1042 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1043 {
1044 IkReal evalcond[2];
1045 IkReal x252=IKcos(j4);
1046 IkReal x253=IKsin(j4);
1047 IkReal x254=((r21)*(sj8));
1048 IkReal x255=((IkReal(1.00000000000000))*(cj8)*(r20));
1049 evalcond[0]=((((IkReal(-1.00000000000000))*(cj7)*(x255)))+(((IkReal(-1.00000000000000))*(cj5)*(x252)))+(((cj7)*(x254)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((sj5)*(x253))));
1050 evalcond[1]=((((sj7)*(x254)))+(((IkReal(-1.00000000000000))*(sj7)*(x255)))+(((cj5)*(x253)))+(((sj5)*(x252)))+(((cj7)*(r22))));
1051 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
1052 {
1053 continue;
1054 }
1055 }
1056 
1057 {
1058 IkReal dummyeval[1];
1059 IkReal gconst71;
1060 IkReal x256=(sj8)*(sj8);
1061 IkReal x257=(cj8)*(cj8);
1062 IkReal x258=((IkReal(2.00000000000000))*(cj8)*(sj8));
1063 gconst71=IKsign(((((r10)*(r11)*(x258)))+(((x256)*((r10)*(r10))))+(((x257)*((r11)*(r11))))+(((r00)*(r01)*(x258)))+(((x257)*((r01)*(r01))))+(((x256)*((r00)*(r00))))));
1064 IkReal x259=(sj8)*(sj8);
1065 IkReal x260=(cj8)*(cj8);
1066 IkReal x261=((IkReal(2.00000000000000))*(cj8)*(sj8));
1067 dummyeval[0]=((((r00)*(r01)*(x261)))+(((x260)*((r01)*(r01))))+(((x260)*((r11)*(r11))))+(((x259)*((r10)*(r10))))+(((x259)*((r00)*(r00))))+(((r10)*(r11)*(x261))));
1068 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1069 {
1070 {
1071 IkReal dummyeval[1];
1072 IkReal gconst72;
1073 IkReal x262=(sj8)*(sj8);
1074 IkReal x263=(cj8)*(cj8);
1075 IkReal x264=((r00)*(r11));
1076 IkReal x265=((r02)*(sj7));
1077 IkReal x266=((cj7)*(x263));
1078 IkReal x267=((IkReal(1.00000000000000))*(r12)*(sj7));
1079 IkReal x268=((IkReal(1.00000000000000))*(r01)*(r10));
1080 IkReal x269=((cj7)*(x262));
1081 gconst72=IKsign(((((r10)*(sj8)*(x265)))+(((x264)*(x269)))+(((x264)*(x266)))+(((IkReal(-1.00000000000000))*(x268)*(x269)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x267)))+(((cj8)*(r11)*(x265)))+(((IkReal(-1.00000000000000))*(x266)*(x268)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x267)))));
1082 IkReal x270=(sj8)*(sj8);
1083 IkReal x271=(cj8)*(cj8);
1084 IkReal x272=((r00)*(r11));
1085 IkReal x273=((r02)*(sj7));
1086 IkReal x274=((cj7)*(x271));
1087 IkReal x275=((IkReal(1.00000000000000))*(r12)*(sj7));
1088 IkReal x276=((IkReal(1.00000000000000))*(r01)*(r10));
1089 IkReal x277=((cj7)*(x270));
1090 dummyeval[0]=((((x272)*(x274)))+(((x272)*(x277)))+(((IkReal(-1.00000000000000))*(x274)*(x276)))+(((r10)*(sj8)*(x273)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x275)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x275)))+(((cj8)*(r11)*(x273)))+(((IkReal(-1.00000000000000))*(x276)*(x277))));
1091 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1092 {
1093 continue;
1094 
1095 } else
1096 {
1097 {
1098 IkReal j3array[1], cj3array[1], sj3array[1];
1099 bool j3valid[1]={false};
1100 _nj3 = 1;
1101 IkReal x278=((cj7)*(cj8));
1102 IkReal x279=((IkReal(1.00000000000000))*(cj7)*(sj8));
1103 if( IKabs(((gconst72)*(((((IkReal(-1.00000000000000))*(r11)*(x279)))+(((r12)*(sj7)))+(((r10)*(x278))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst72)*(((((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x279)))+(((r00)*(x278))))))) < IKFAST_ATAN2_MAGTHRESH )
1104  continue;
1105 j3array[0]=IKatan2(((gconst72)*(((((IkReal(-1.00000000000000))*(r11)*(x279)))+(((r12)*(sj7)))+(((r10)*(x278)))))), ((gconst72)*(((((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x279)))+(((r00)*(x278)))))));
1106 sj3array[0]=IKsin(j3array[0]);
1107 cj3array[0]=IKcos(j3array[0]);
1108 if( j3array[0] > IKPI )
1109 {
1110  j3array[0]-=IK2PI;
1111 }
1112 else if( j3array[0] < -IKPI )
1113 { j3array[0]+=IK2PI;
1114 }
1115 j3valid[0] = true;
1116 for(int ij3 = 0; ij3 < 1; ++ij3)
1117 {
1118 if( !j3valid[ij3] )
1119 {
1120  continue;
1121 }
1122 _ij3[0] = ij3; _ij3[1] = -1;
1123 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1124 {
1125 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1126 {
1127  j3valid[iij3]=false; _ij3[1] = iij3; break;
1128 }
1129 }
1130 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1131 {
1132 IkReal evalcond[6];
1133 IkReal x280=IKsin(j3);
1134 IkReal x281=IKcos(j3);
1135 IkReal x282=((r01)*(sj8));
1136 IkReal x283=((cj8)*(r00));
1137 IkReal x284=((r00)*(sj8));
1138 IkReal x285=((cj8)*(r11));
1139 IkReal x286=((r11)*(sj8));
1140 IkReal x287=((r10)*(sj8));
1141 IkReal x288=((cj8)*(r10));
1142 IkReal x289=((cj7)*(x280));
1143 IkReal x290=((sj7)*(x281));
1144 IkReal x291=((IkReal(1.00000000000000))*(x280));
1145 IkReal x292=((IkReal(1.00000000000000))*(x281));
1146 IkReal x293=((cj8)*(x280));
1147 IkReal x294=((IkReal(1.00000000000000))*(x286));
1148 IkReal x295=((sj7)*(x280));
1149 IkReal x296=((cj7)*(x281));
1150 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x285)*(x292)))+(((r01)*(x293)))+(((IkReal(-1.00000000000000))*(x287)*(x292)))+(((x280)*(x284))));
1151 evalcond[1]=((((IkReal(-1.00000000000000))*(x284)*(x292)))+(((IkReal(-1.00000000000000))*(x285)*(x291)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x292)))+(((IkReal(-1.00000000000000))*(x287)*(x291))));
1152 evalcond[2]=((((r12)*(x290)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x291)))+(((IkReal(-1.00000000000000))*(x283)*(x289)))+(((x282)*(x289)))+(((x288)*(x296)))+(((IkReal(-1.00000000000000))*(cj7)*(x286)*(x292))));
1153 evalcond[3]=((((IkReal(-1.00000000000000))*(cj7)*(r12)*(x292)))+(((IkReal(-1.00000000000000))*(x290)*(x294)))+(((IkReal(-1.00000000000000))*(sj7)*(x283)*(x291)))+(((x282)*(x295)))+(((r02)*(x289)))+(((x288)*(x290))));
1154 evalcond[4]=((((r12)*(x295)))+(((IkReal(-1.00000000000000))*(cj7)*(x282)*(x292)))+(((IkReal(-1.00000000000000))*(x289)*(x294)))+(((x283)*(x296)))+(((cj5)*(sj4)))+(((cj4)*(sj5)))+(((x288)*(x289)))+(((r02)*(x290))));
1155 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x289)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x292)))+(((x283)*(x290)))+(((IkReal(-1.00000000000000))*(x282)*(x290)))+(((cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(sj7)*(x286)*(x291)))+(((x288)*(x295))));
1156 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
1157 {
1158 continue;
1159 }
1160 }
1161 
1162 {
1163 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1164 vinfos[0].jointtype = 1;
1165 vinfos[0].foffset = j3;
1166 vinfos[0].indices[0] = _ij3[0];
1167 vinfos[0].indices[1] = _ij3[1];
1168 vinfos[0].maxsolutions = _nj3;
1169 vinfos[1].jointtype = 1;
1170 vinfos[1].foffset = j4;
1171 vinfos[1].indices[0] = _ij4[0];
1172 vinfos[1].indices[1] = _ij4[1];
1173 vinfos[1].maxsolutions = _nj4;
1174 vinfos[2].jointtype = 1;
1175 vinfos[2].foffset = j5;
1176 vinfos[2].indices[0] = _ij5[0];
1177 vinfos[2].indices[1] = _ij5[1];
1178 vinfos[2].maxsolutions = _nj5;
1179 vinfos[3].jointtype = 1;
1180 vinfos[3].foffset = j6;
1181 vinfos[3].indices[0] = _ij6[0];
1182 vinfos[3].indices[1] = _ij6[1];
1183 vinfos[3].maxsolutions = _nj6;
1184 vinfos[4].jointtype = 1;
1185 vinfos[4].foffset = j7;
1186 vinfos[4].indices[0] = _ij7[0];
1187 vinfos[4].indices[1] = _ij7[1];
1188 vinfos[4].maxsolutions = _nj7;
1189 vinfos[5].jointtype = 1;
1190 vinfos[5].foffset = j8;
1191 vinfos[5].indices[0] = _ij8[0];
1192 vinfos[5].indices[1] = _ij8[1];
1193 vinfos[5].maxsolutions = _nj8;
1194 std::vector<int> vfree(0);
1195 solutions.AddSolution(vinfos,vfree);
1196 }
1197 }
1198 }
1199 
1200 }
1201 
1202 }
1203 
1204 } else
1205 {
1206 {
1207 IkReal j3array[1], cj3array[1], sj3array[1];
1208 bool j3valid[1]={false};
1209 _nj3 = 1;
1210 if( IKabs(((gconst71)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst71)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
1211  continue;
1212 j3array[0]=IKatan2(((gconst71)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst71)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
1213 sj3array[0]=IKsin(j3array[0]);
1214 cj3array[0]=IKcos(j3array[0]);
1215 if( j3array[0] > IKPI )
1216 {
1217  j3array[0]-=IK2PI;
1218 }
1219 else if( j3array[0] < -IKPI )
1220 { j3array[0]+=IK2PI;
1221 }
1222 j3valid[0] = true;
1223 for(int ij3 = 0; ij3 < 1; ++ij3)
1224 {
1225 if( !j3valid[ij3] )
1226 {
1227  continue;
1228 }
1229 _ij3[0] = ij3; _ij3[1] = -1;
1230 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1231 {
1232 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1233 {
1234  j3valid[iij3]=false; _ij3[1] = iij3; break;
1235 }
1236 }
1237 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1238 {
1239 IkReal evalcond[6];
1240 IkReal x297=IKsin(j3);
1241 IkReal x298=IKcos(j3);
1242 IkReal x299=((r01)*(sj8));
1243 IkReal x300=((cj8)*(r00));
1244 IkReal x301=((r00)*(sj8));
1245 IkReal x302=((cj8)*(r11));
1246 IkReal x303=((r11)*(sj8));
1247 IkReal x304=((r10)*(sj8));
1248 IkReal x305=((cj8)*(r10));
1249 IkReal x306=((cj7)*(x297));
1250 IkReal x307=((sj7)*(x298));
1251 IkReal x308=((IkReal(1.00000000000000))*(x297));
1252 IkReal x309=((IkReal(1.00000000000000))*(x298));
1253 IkReal x310=((cj8)*(x297));
1254 IkReal x311=((IkReal(1.00000000000000))*(x303));
1255 IkReal x312=((sj7)*(x297));
1256 IkReal x313=((cj7)*(x298));
1257 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x302)*(x309)))+(((r01)*(x310)))+(((x297)*(x301)))+(((IkReal(-1.00000000000000))*(x304)*(x309))));
1258 evalcond[1]=((((IkReal(-1.00000000000000))*(x301)*(x309)))+(((IkReal(-1.00000000000000))*(x302)*(x308)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x309)))+(((IkReal(-1.00000000000000))*(x304)*(x308))));
1259 evalcond[2]=((((x305)*(x313)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x308)))+(((IkReal(-1.00000000000000))*(cj7)*(x303)*(x309)))+(((x299)*(x306)))+(((IkReal(-1.00000000000000))*(x300)*(x306)))+(((r12)*(x307))));
1260 evalcond[3]=((((IkReal(-1.00000000000000))*(sj7)*(x300)*(x308)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x309)))+(((x299)*(x312)))+(((r02)*(x306)))+(((x305)*(x307)))+(((IkReal(-1.00000000000000))*(x307)*(x311))));
1261 evalcond[4]=((((IkReal(-1.00000000000000))*(cj7)*(x299)*(x309)))+(((x300)*(x313)))+(((cj5)*(sj4)))+(((r02)*(x307)))+(((cj4)*(sj5)))+(((IkReal(-1.00000000000000))*(x306)*(x311)))+(((x305)*(x306)))+(((r12)*(x312))));
1262 evalcond[5]=((((x305)*(x312)))+(((IkReal(-1.00000000000000))*(r12)*(x306)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x309)))+(((cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(x299)*(x307)))+(((IkReal(-1.00000000000000))*(sj7)*(x303)*(x308)))+(((x300)*(x307)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5))));
1263 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
1264 {
1265 continue;
1266 }
1267 }
1268 
1269 {
1270 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1271 vinfos[0].jointtype = 1;
1272 vinfos[0].foffset = j3;
1273 vinfos[0].indices[0] = _ij3[0];
1274 vinfos[0].indices[1] = _ij3[1];
1275 vinfos[0].maxsolutions = _nj3;
1276 vinfos[1].jointtype = 1;
1277 vinfos[1].foffset = j4;
1278 vinfos[1].indices[0] = _ij4[0];
1279 vinfos[1].indices[1] = _ij4[1];
1280 vinfos[1].maxsolutions = _nj4;
1281 vinfos[2].jointtype = 1;
1282 vinfos[2].foffset = j5;
1283 vinfos[2].indices[0] = _ij5[0];
1284 vinfos[2].indices[1] = _ij5[1];
1285 vinfos[2].maxsolutions = _nj5;
1286 vinfos[3].jointtype = 1;
1287 vinfos[3].foffset = j6;
1288 vinfos[3].indices[0] = _ij6[0];
1289 vinfos[3].indices[1] = _ij6[1];
1290 vinfos[3].maxsolutions = _nj6;
1291 vinfos[4].jointtype = 1;
1292 vinfos[4].foffset = j7;
1293 vinfos[4].indices[0] = _ij7[0];
1294 vinfos[4].indices[1] = _ij7[1];
1295 vinfos[4].maxsolutions = _nj7;
1296 vinfos[5].jointtype = 1;
1297 vinfos[5].foffset = j8;
1298 vinfos[5].indices[0] = _ij8[0];
1299 vinfos[5].indices[1] = _ij8[1];
1300 vinfos[5].maxsolutions = _nj8;
1301 std::vector<int> vfree(0);
1302 solutions.AddSolution(vinfos,vfree);
1303 }
1304 }
1305 }
1306 
1307 }
1308 
1309 }
1310 }
1311 }
1312 
1313 }
1314 
1315 }
1316 
1317 } else
1318 {
1319 {
1320 IkReal j3array[1], cj3array[1], sj3array[1];
1321 bool j3valid[1]={false};
1322 _nj3 = 1;
1323 if( IKabs(((gconst66)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst66)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
1324  continue;
1325 j3array[0]=IKatan2(((gconst66)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst66)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
1326 sj3array[0]=IKsin(j3array[0]);
1327 cj3array[0]=IKcos(j3array[0]);
1328 if( j3array[0] > IKPI )
1329 {
1330  j3array[0]-=IK2PI;
1331 }
1332 else if( j3array[0] < -IKPI )
1333 { j3array[0]+=IK2PI;
1334 }
1335 j3valid[0] = true;
1336 for(int ij3 = 0; ij3 < 1; ++ij3)
1337 {
1338 if( !j3valid[ij3] )
1339 {
1340  continue;
1341 }
1342 _ij3[0] = ij3; _ij3[1] = -1;
1343 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1344 {
1345 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1346 {
1347  j3valid[iij3]=false; _ij3[1] = iij3; break;
1348 }
1349 }
1350 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1351 {
1352 IkReal evalcond[4];
1353 IkReal x314=IKsin(j3);
1354 IkReal x315=IKcos(j3);
1355 IkReal x316=((IkReal(1.00000000000000))*(sj8));
1356 IkReal x317=((IkReal(1.00000000000000))*(cj8));
1357 IkReal x318=((r01)*(sj8));
1358 IkReal x319=((cj8)*(r10));
1359 IkReal x320=((sj7)*(x315));
1360 IkReal x321=((cj7)*(x314));
1361 IkReal x322=((r00)*(x314));
1362 IkReal x323=((sj7)*(x314));
1363 IkReal x324=((cj7)*(x315));
1364 evalcond[0]=((IkReal(1.00000000000000))+(((cj8)*(r01)*(x314)))+(((IkReal(-1.00000000000000))*(r11)*(x315)*(x317)))+(((IkReal(-1.00000000000000))*(r10)*(x315)*(x316)))+(((sj8)*(x322))));
1365 evalcond[1]=((((IkReal(-1.00000000000000))*(r10)*(x314)*(x316)))+(((IkReal(-1.00000000000000))*(r01)*(x315)*(x317)))+(((IkReal(-1.00000000000000))*(r11)*(x314)*(x317)))+(((IkReal(-1.00000000000000))*(r00)*(x315)*(x316))));
1366 evalcond[2]=((((x318)*(x321)))+(((r12)*(x320)))+(((IkReal(-1.00000000000000))*(r00)*(x317)*(x321)))+(((IkReal(-1.00000000000000))*(r02)*(x323)))+(((IkReal(-1.00000000000000))*(r11)*(x316)*(x324)))+(((x319)*(x324))));
1367 evalcond[3]=((((x318)*(x323)))+(((r02)*(x321)))+(((IkReal(-1.00000000000000))*(r12)*(x324)))+(((IkReal(-1.00000000000000))*(sj7)*(x317)*(x322)))+(((IkReal(-1.00000000000000))*(r11)*(x316)*(x320)))+(((x319)*(x320))));
1368 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
1369 {
1370 continue;
1371 }
1372 }
1373 
1374 {
1375 IkReal dummyeval[1];
1376 IkReal gconst69;
1377 gconst69=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
1378 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
1379 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1380 {
1381 {
1382 IkReal dummyeval[1];
1383 IkReal gconst70;
1384 gconst70=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
1385 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
1386 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1387 {
1388 continue;
1389 
1390 } else
1391 {
1392 {
1393 IkReal j4array[1], cj4array[1], sj4array[1];
1394 bool j4valid[1]={false};
1395 _nj4 = 1;
1396 IkReal x325=((cj3)*(cj5));
1397 IkReal x326=((r02)*(sj7));
1398 IkReal x327=((cj8)*(r00));
1399 IkReal x328=((r22)*(sj7));
1400 IkReal x329=((cj5)*(sj3));
1401 IkReal x330=((cj7)*(cj8));
1402 IkReal x331=((IkReal(1.00000000000000))*(sj5));
1403 IkReal x332=((sj3)*(sj5));
1404 IkReal x333=((r12)*(sj7));
1405 IkReal x334=((cj3)*(cj7)*(sj5));
1406 IkReal x335=((IkReal(1.00000000000000))*(cj7)*(sj8));
1407 if( IKabs(((gconst70)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((x325)*(x326)))+(((cj7)*(x325)*(x327)))+(((IkReal(-1.00000000000000))*(x328)*(x331)))+(((x329)*(x333)))+(((r10)*(x329)*(x330)))+(((IkReal(-1.00000000000000))*(r01)*(x325)*(x335)))+(((IkReal(-1.00000000000000))*(r11)*(x329)*(x335)))+(((IkReal(-1.00000000000000))*(r20)*(x330)*(x331))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst70)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x335)))+(((x332)*(x333)))+(((cj5)*(x328)))+(((x327)*(x334)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x331)))+(((cj3)*(sj5)*(x326)))+(((cj5)*(r20)*(x330)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x331)))+(((r10)*(x330)*(x332))))))) < IKFAST_ATAN2_MAGTHRESH )
1408  continue;
1409 j4array[0]=IKatan2(((gconst70)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((x325)*(x326)))+(((cj7)*(x325)*(x327)))+(((IkReal(-1.00000000000000))*(x328)*(x331)))+(((x329)*(x333)))+(((r10)*(x329)*(x330)))+(((IkReal(-1.00000000000000))*(r01)*(x325)*(x335)))+(((IkReal(-1.00000000000000))*(r11)*(x329)*(x335)))+(((IkReal(-1.00000000000000))*(r20)*(x330)*(x331)))))), ((gconst70)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x335)))+(((x332)*(x333)))+(((cj5)*(x328)))+(((x327)*(x334)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x331)))+(((cj3)*(sj5)*(x326)))+(((cj5)*(r20)*(x330)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x331)))+(((r10)*(x330)*(x332)))))));
1410 sj4array[0]=IKsin(j4array[0]);
1411 cj4array[0]=IKcos(j4array[0]);
1412 if( j4array[0] > IKPI )
1413 {
1414  j4array[0]-=IK2PI;
1415 }
1416 else if( j4array[0] < -IKPI )
1417 { j4array[0]+=IK2PI;
1418 }
1419 j4valid[0] = true;
1420 for(int ij4 = 0; ij4 < 1; ++ij4)
1421 {
1422 if( !j4valid[ij4] )
1423 {
1424  continue;
1425 }
1426 _ij4[0] = ij4; _ij4[1] = -1;
1427 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1428 {
1429 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1430 {
1431  j4valid[iij4]=false; _ij4[1] = iij4; break;
1432 }
1433 }
1434 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1435 {
1436 IkReal evalcond[4];
1437 IkReal x336=IKcos(j4);
1438 IkReal x337=IKsin(j4);
1439 IkReal x338=((IkReal(1.00000000000000))*(cj7));
1440 IkReal x339=((cj8)*(r20));
1441 IkReal x340=((cj3)*(r02));
1442 IkReal x341=((IkReal(1.00000000000000))*(sj7));
1443 IkReal x342=((sj3)*(sj7));
1444 IkReal x343=((r21)*(sj8));
1445 IkReal x344=((cj8)*(r10));
1446 IkReal x345=((sj5)*(x336));
1447 IkReal x346=((cj5)*(x337));
1448 IkReal x347=((r11)*(sj3)*(sj8));
1449 IkReal x348=((cj3)*(cj8)*(r00));
1450 IkReal x349=((cj5)*(x336));
1451 IkReal x350=((cj3)*(r01)*(sj8));
1452 IkReal x351=((sj5)*(x337));
1453 IkReal x352=((x346)+(x345));
1454 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x341)))+(((IkReal(-1.00000000000000))*(x338)*(x339)))+(x351)+(((cj7)*(x343)))+(((IkReal(-1.00000000000000))*(x349))));
1455 evalcond[1]=((x352)+(((sj7)*(x343)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x339)*(x341))));
1456 evalcond[2]=((((IkReal(-1.00000000000000))*(x338)*(x350)))+(x352)+(((cj7)*(sj3)*(x344)))+(((cj7)*(x348)))+(((sj7)*(x340)))+(((IkReal(-1.00000000000000))*(x338)*(x347)))+(((r12)*(x342))));
1457 evalcond[3]=((((IkReal(-1.00000000000000))*(x341)*(x350)))+(((IkReal(-1.00000000000000))*(x351)))+(x349)+(((IkReal(-1.00000000000000))*(x341)*(x347)))+(((sj7)*(x348)))+(((IkReal(-1.00000000000000))*(x338)*(x340)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x338)))+(((x342)*(x344))));
1458 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
1459 {
1460 continue;
1461 }
1462 }
1463 
1464 {
1465 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1466 vinfos[0].jointtype = 1;
1467 vinfos[0].foffset = j3;
1468 vinfos[0].indices[0] = _ij3[0];
1469 vinfos[0].indices[1] = _ij3[1];
1470 vinfos[0].maxsolutions = _nj3;
1471 vinfos[1].jointtype = 1;
1472 vinfos[1].foffset = j4;
1473 vinfos[1].indices[0] = _ij4[0];
1474 vinfos[1].indices[1] = _ij4[1];
1475 vinfos[1].maxsolutions = _nj4;
1476 vinfos[2].jointtype = 1;
1477 vinfos[2].foffset = j5;
1478 vinfos[2].indices[0] = _ij5[0];
1479 vinfos[2].indices[1] = _ij5[1];
1480 vinfos[2].maxsolutions = _nj5;
1481 vinfos[3].jointtype = 1;
1482 vinfos[3].foffset = j6;
1483 vinfos[3].indices[0] = _ij6[0];
1484 vinfos[3].indices[1] = _ij6[1];
1485 vinfos[3].maxsolutions = _nj6;
1486 vinfos[4].jointtype = 1;
1487 vinfos[4].foffset = j7;
1488 vinfos[4].indices[0] = _ij7[0];
1489 vinfos[4].indices[1] = _ij7[1];
1490 vinfos[4].maxsolutions = _nj7;
1491 vinfos[5].jointtype = 1;
1492 vinfos[5].foffset = j8;
1493 vinfos[5].indices[0] = _ij8[0];
1494 vinfos[5].indices[1] = _ij8[1];
1495 vinfos[5].maxsolutions = _nj8;
1496 std::vector<int> vfree(0);
1497 solutions.AddSolution(vinfos,vfree);
1498 }
1499 }
1500 }
1501 
1502 }
1503 
1504 }
1505 
1506 } else
1507 {
1508 {
1509 IkReal j4array[1], cj4array[1], sj4array[1];
1510 bool j4valid[1]={false};
1511 _nj4 = 1;
1512 IkReal x353=((r21)*(sj8));
1513 IkReal x354=((sj5)*(sj7));
1514 IkReal x355=((cj5)*(sj7));
1515 IkReal x356=((cj5)*(cj7));
1516 IkReal x357=((cj8)*(r20));
1517 IkReal x358=((cj7)*(sj5));
1518 if( IKabs(((gconst69)*(((((IkReal(-1.00000000000000))*(r22)*(x354)))+(((IkReal(-1.00000000000000))*(x357)*(x358)))+(((x353)*(x358)))+(((x353)*(x355)))+(((r22)*(x356)))+(((IkReal(-1.00000000000000))*(x355)*(x357))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst69)*(((((x356)*(x357)))+(((IkReal(-1.00000000000000))*(x353)*(x356)))+(((x353)*(x354)))+(((r22)*(x355)))+(((r22)*(x358)))+(((IkReal(-1.00000000000000))*(x354)*(x357))))))) < IKFAST_ATAN2_MAGTHRESH )
1519  continue;
1520 j4array[0]=IKatan2(((gconst69)*(((((IkReal(-1.00000000000000))*(r22)*(x354)))+(((IkReal(-1.00000000000000))*(x357)*(x358)))+(((x353)*(x358)))+(((x353)*(x355)))+(((r22)*(x356)))+(((IkReal(-1.00000000000000))*(x355)*(x357)))))), ((gconst69)*(((((x356)*(x357)))+(((IkReal(-1.00000000000000))*(x353)*(x356)))+(((x353)*(x354)))+(((r22)*(x355)))+(((r22)*(x358)))+(((IkReal(-1.00000000000000))*(x354)*(x357)))))));
1521 sj4array[0]=IKsin(j4array[0]);
1522 cj4array[0]=IKcos(j4array[0]);
1523 if( j4array[0] > IKPI )
1524 {
1525  j4array[0]-=IK2PI;
1526 }
1527 else if( j4array[0] < -IKPI )
1528 { j4array[0]+=IK2PI;
1529 }
1530 j4valid[0] = true;
1531 for(int ij4 = 0; ij4 < 1; ++ij4)
1532 {
1533 if( !j4valid[ij4] )
1534 {
1535  continue;
1536 }
1537 _ij4[0] = ij4; _ij4[1] = -1;
1538 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1539 {
1540 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1541 {
1542  j4valid[iij4]=false; _ij4[1] = iij4; break;
1543 }
1544 }
1545 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1546 {
1547 IkReal evalcond[4];
1548 IkReal x359=IKcos(j4);
1549 IkReal x360=IKsin(j4);
1550 IkReal x361=((IkReal(1.00000000000000))*(cj7));
1551 IkReal x362=((cj8)*(r20));
1552 IkReal x363=((cj3)*(r02));
1553 IkReal x364=((IkReal(1.00000000000000))*(sj7));
1554 IkReal x365=((sj3)*(sj7));
1555 IkReal x366=((r21)*(sj8));
1556 IkReal x367=((cj8)*(r10));
1557 IkReal x368=((sj5)*(x359));
1558 IkReal x369=((cj5)*(x360));
1559 IkReal x370=((r11)*(sj3)*(sj8));
1560 IkReal x371=((cj3)*(cj8)*(r00));
1561 IkReal x372=((cj5)*(x359));
1562 IkReal x373=((cj3)*(r01)*(sj8));
1563 IkReal x374=((sj5)*(x360));
1564 IkReal x375=((x368)+(x369));
1565 evalcond[0]=((((cj7)*(x366)))+(((IkReal(-1.00000000000000))*(x372)))+(((IkReal(-1.00000000000000))*(x361)*(x362)))+(x374)+(((IkReal(-1.00000000000000))*(r22)*(x364))));
1566 evalcond[1]=((((IkReal(-1.00000000000000))*(x362)*(x364)))+(x375)+(((sj7)*(x366)))+(((cj7)*(r22))));
1567 evalcond[2]=((((cj7)*(x371)))+(((IkReal(-1.00000000000000))*(x361)*(x373)))+(((IkReal(-1.00000000000000))*(x361)*(x370)))+(x375)+(((r12)*(x365)))+(((sj7)*(x363)))+(((cj7)*(sj3)*(x367))));
1568 evalcond[3]=((((IkReal(-1.00000000000000))*(x374)))+(((IkReal(-1.00000000000000))*(x361)*(x363)))+(((x365)*(x367)))+(x372)+(((sj7)*(x371)))+(((IkReal(-1.00000000000000))*(x364)*(x370)))+(((IkReal(-1.00000000000000))*(x364)*(x373)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x361))));
1569 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
1570 {
1571 continue;
1572 }
1573 }
1574 
1575 {
1576 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1577 vinfos[0].jointtype = 1;
1578 vinfos[0].foffset = j3;
1579 vinfos[0].indices[0] = _ij3[0];
1580 vinfos[0].indices[1] = _ij3[1];
1581 vinfos[0].maxsolutions = _nj3;
1582 vinfos[1].jointtype = 1;
1583 vinfos[1].foffset = j4;
1584 vinfos[1].indices[0] = _ij4[0];
1585 vinfos[1].indices[1] = _ij4[1];
1586 vinfos[1].maxsolutions = _nj4;
1587 vinfos[2].jointtype = 1;
1588 vinfos[2].foffset = j5;
1589 vinfos[2].indices[0] = _ij5[0];
1590 vinfos[2].indices[1] = _ij5[1];
1591 vinfos[2].maxsolutions = _nj5;
1592 vinfos[3].jointtype = 1;
1593 vinfos[3].foffset = j6;
1594 vinfos[3].indices[0] = _ij6[0];
1595 vinfos[3].indices[1] = _ij6[1];
1596 vinfos[3].maxsolutions = _nj6;
1597 vinfos[4].jointtype = 1;
1598 vinfos[4].foffset = j7;
1599 vinfos[4].indices[0] = _ij7[0];
1600 vinfos[4].indices[1] = _ij7[1];
1601 vinfos[4].maxsolutions = _nj7;
1602 vinfos[5].jointtype = 1;
1603 vinfos[5].foffset = j8;
1604 vinfos[5].indices[0] = _ij8[0];
1605 vinfos[5].indices[1] = _ij8[1];
1606 vinfos[5].maxsolutions = _nj8;
1607 std::vector<int> vfree(0);
1608 solutions.AddSolution(vinfos,vfree);
1609 }
1610 }
1611 }
1612 
1613 }
1614 
1615 }
1616 }
1617 }
1618 
1619 }
1620 
1621 }
1622 }
1623 }
1624 
1625 } else
1626 {
1627 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
1628 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
1629 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
1630 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 )
1631 {
1632 {
1633 IkReal j5array[1], cj5array[1], sj5array[1];
1634 bool j5valid[1]={false};
1635 _nj5 = 1;
1636 IkReal x376=((IkReal(4.00000000000000))*(sj7));
1637 IkReal x377=((npy)*(sj8));
1638 IkReal x378=((IkReal(4.00000000000000))*(cj7));
1639 IkReal x379=((cj8)*(npx));
1640 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-0.360000000000000))*(sj7)))+(((x376)*(x379)))+(((IkReal(-1.00000000000000))*(x376)*(x377)))+(((IkReal(-1.00000000000000))*(npz)*(x378))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((npz)*(x376)))+(((IkReal(-1.00000000000000))*(x377)*(x378)))+(((x378)*(x379)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-0.360000000000000))*(sj7)))+(((x376)*(x379)))+(((IkReal(-1.00000000000000))*(x376)*(x377)))+(((IkReal(-1.00000000000000))*(npz)*(x378)))))+IKsqr(((IkReal(-0.940000000000000))+(((npz)*(x376)))+(((IkReal(-1.00000000000000))*(x377)*(x378)))+(((x378)*(x379)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
1641  continue;
1642 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-0.360000000000000))*(sj7)))+(((x376)*(x379)))+(((IkReal(-1.00000000000000))*(x376)*(x377)))+(((IkReal(-1.00000000000000))*(npz)*(x378)))), ((IkReal(-0.940000000000000))+(((npz)*(x376)))+(((IkReal(-1.00000000000000))*(x377)*(x378)))+(((x378)*(x379)))+(((IkReal(-0.360000000000000))*(cj7)))));
1643 sj5array[0]=IKsin(j5array[0]);
1644 cj5array[0]=IKcos(j5array[0]);
1645 if( j5array[0] > IKPI )
1646 {
1647  j5array[0]-=IK2PI;
1648 }
1649 else if( j5array[0] < -IKPI )
1650 { j5array[0]+=IK2PI;
1651 }
1652 j5valid[0] = true;
1653 for(int ij5 = 0; ij5 < 1; ++ij5)
1654 {
1655 if( !j5valid[ij5] )
1656 {
1657  continue;
1658 }
1659 _ij5[0] = ij5; _ij5[1] = -1;
1660 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1661 {
1662 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1663 {
1664  j5valid[iij5]=false; _ij5[1] = iij5; break;
1665 }
1666 }
1667 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1668 {
1669 IkReal evalcond[2];
1670 IkReal x380=((IkReal(1.00000000000000))*(sj7));
1671 IkReal x381=((npy)*(sj8));
1672 IkReal x382=((cj8)*(npx));
1673 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x380)))+(((IkReal(0.0900000000000000))*(cj7)))+(((cj7)*(x381)))+(((IkReal(-1.00000000000000))*(cj7)*(x382)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
1674 evalcond[1]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x380)*(x382)))+(((IkReal(0.250000000000000))*(IKsin(j5))))+(((cj7)*(npz)))+(((sj7)*(x381))));
1675 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
1676 {
1677 continue;
1678 }
1679 }
1680 
1681 {
1682 IkReal dummyeval[1];
1683 IkReal gconst75;
1684 IkReal x383=(cj8)*(cj8);
1685 IkReal x384=(sj8)*(sj8);
1686 IkReal x385=((IkReal(2.00000000000000))*(cj8)*(sj8));
1687 IkReal x386=((IkReal(1.00000000000000))*(x383));
1688 IkReal x387=((IkReal(1.00000000000000))*(x384));
1689 gconst75=IKsign(((((IkReal(-1.00000000000000))*(x387)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x386)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x385)))+(((IkReal(-1.00000000000000))*(x386)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x385)))+(((IkReal(-1.00000000000000))*(x387)*((r10)*(r10))))));
1690 IkReal x388=(cj8)*(cj8);
1691 IkReal x389=(sj8)*(sj8);
1692 IkReal x390=((IkReal(2.00000000000000))*(cj8)*(sj8));
1693 IkReal x391=((IkReal(1.00000000000000))*(x388));
1694 IkReal x392=((IkReal(1.00000000000000))*(x389));
1695 dummyeval[0]=((((IkReal(-1.00000000000000))*(x392)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x390)))+(((IkReal(-1.00000000000000))*(x391)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x390)))+(((IkReal(-1.00000000000000))*(x391)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x392)*((r10)*(r10)))));
1696 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1697 {
1698 {
1699 IkReal dummyeval[1];
1700 IkReal gconst77;
1701 gconst77=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
1702 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
1703 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1704 {
1705 {
1706 IkReal dummyeval[1];
1707 IkReal gconst76;
1708 IkReal x393=(sj8)*(sj8);
1709 IkReal x394=(cj8)*(cj8);
1710 IkReal x395=((sj7)*(sj8));
1711 IkReal x396=((IkReal(1.00000000000000))*(r02));
1712 IkReal x397=((r01)*(r10));
1713 IkReal x398=((cj8)*(sj7));
1714 IkReal x399=((cj7)*(x393));
1715 IkReal x400=((IkReal(1.00000000000000))*(r00)*(r11));
1716 IkReal x401=((cj7)*(x394));
1717 gconst76=IKsign(((((x397)*(x401)))+(((r01)*(r12)*(x398)))+(((IkReal(-1.00000000000000))*(x400)*(x401)))+(((r00)*(r12)*(x395)))+(((IkReal(-1.00000000000000))*(x399)*(x400)))+(((x397)*(x399)))+(((IkReal(-1.00000000000000))*(r10)*(x395)*(x396)))+(((IkReal(-1.00000000000000))*(r11)*(x396)*(x398)))));
1718 IkReal x402=(sj8)*(sj8);
1719 IkReal x403=(cj8)*(cj8);
1720 IkReal x404=((sj7)*(sj8));
1721 IkReal x405=((IkReal(1.00000000000000))*(r02));
1722 IkReal x406=((r01)*(r10));
1723 IkReal x407=((cj8)*(sj7));
1724 IkReal x408=((cj7)*(x402));
1725 IkReal x409=((IkReal(1.00000000000000))*(r00)*(r11));
1726 IkReal x410=((cj7)*(x403));
1727 dummyeval[0]=((((r01)*(r12)*(x407)))+(((IkReal(-1.00000000000000))*(r10)*(x404)*(x405)))+(((IkReal(-1.00000000000000))*(r11)*(x405)*(x407)))+(((x406)*(x410)))+(((x406)*(x408)))+(((r00)*(r12)*(x404)))+(((IkReal(-1.00000000000000))*(x409)*(x410)))+(((IkReal(-1.00000000000000))*(x408)*(x409))));
1728 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1729 {
1730 continue;
1731 
1732 } else
1733 {
1734 {
1735 IkReal j3array[1], cj3array[1], sj3array[1];
1736 bool j3valid[1]={false};
1737 _nj3 = 1;
1738 IkReal x411=((cj7)*(cj8));
1739 IkReal x412=((IkReal(1.00000000000000))*(cj7)*(sj8));
1740 if( IKabs(((gconst76)*(((((r12)*(sj7)))+(((r10)*(x411)))+(((IkReal(-1.00000000000000))*(r11)*(x412))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst76)*(((((r02)*(sj7)))+(((r00)*(x411)))+(((IkReal(-1.00000000000000))*(r01)*(x412))))))) < IKFAST_ATAN2_MAGTHRESH )
1741  continue;
1742 j3array[0]=IKatan2(((gconst76)*(((((r12)*(sj7)))+(((r10)*(x411)))+(((IkReal(-1.00000000000000))*(r11)*(x412)))))), ((gconst76)*(((((r02)*(sj7)))+(((r00)*(x411)))+(((IkReal(-1.00000000000000))*(r01)*(x412)))))));
1743 sj3array[0]=IKsin(j3array[0]);
1744 cj3array[0]=IKcos(j3array[0]);
1745 if( j3array[0] > IKPI )
1746 {
1747  j3array[0]-=IK2PI;
1748 }
1749 else if( j3array[0] < -IKPI )
1750 { j3array[0]+=IK2PI;
1751 }
1752 j3valid[0] = true;
1753 for(int ij3 = 0; ij3 < 1; ++ij3)
1754 {
1755 if( !j3valid[ij3] )
1756 {
1757  continue;
1758 }
1759 _ij3[0] = ij3; _ij3[1] = -1;
1760 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1761 {
1762 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1763 {
1764  j3valid[iij3]=false; _ij3[1] = iij3; break;
1765 }
1766 }
1767 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1768 {
1769 IkReal evalcond[4];
1770 IkReal x413=IKsin(j3);
1771 IkReal x414=IKcos(j3);
1772 IkReal x415=((IkReal(1.00000000000000))*(sj8));
1773 IkReal x416=((IkReal(1.00000000000000))*(cj8));
1774 IkReal x417=((r01)*(sj8));
1775 IkReal x418=((cj8)*(r10));
1776 IkReal x419=((sj7)*(x414));
1777 IkReal x420=((cj7)*(x413));
1778 IkReal x421=((r00)*(x413));
1779 IkReal x422=((sj7)*(x413));
1780 IkReal x423=((cj7)*(x414));
1781 evalcond[0]=((IkReal(-1.00000000000000))+(((sj8)*(x421)))+(((IkReal(-1.00000000000000))*(r11)*(x414)*(x416)))+(((IkReal(-1.00000000000000))*(r10)*(x414)*(x415)))+(((cj8)*(r01)*(x413))));
1782 evalcond[1]=((((IkReal(-1.00000000000000))*(r11)*(x413)*(x416)))+(((IkReal(-1.00000000000000))*(r01)*(x414)*(x416)))+(((IkReal(-1.00000000000000))*(r00)*(x414)*(x415)))+(((IkReal(-1.00000000000000))*(r10)*(x413)*(x415))));
1783 evalcond[2]=((((r12)*(x419)))+(((IkReal(-1.00000000000000))*(r02)*(x422)))+(((IkReal(-1.00000000000000))*(r00)*(x416)*(x420)))+(((x418)*(x423)))+(((IkReal(-1.00000000000000))*(r11)*(x415)*(x423)))+(((x417)*(x420))));
1784 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x423)))+(((IkReal(-1.00000000000000))*(sj7)*(x416)*(x421)))+(((r02)*(x420)))+(((IkReal(-1.00000000000000))*(r11)*(x415)*(x419)))+(((x418)*(x419)))+(((x417)*(x422))));
1785 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
1786 {
1787 continue;
1788 }
1789 }
1790 
1791 {
1792 IkReal dummyeval[1];
1793 IkReal gconst78;
1794 gconst78=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
1795 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
1796 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1797 {
1798 {
1799 IkReal dummyeval[1];
1800 IkReal gconst79;
1801 gconst79=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
1802 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
1803 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1804 {
1805 continue;
1806 
1807 } else
1808 {
1809 {
1810 IkReal j4array[1], cj4array[1], sj4array[1];
1811 bool j4valid[1]={false};
1812 _nj4 = 1;
1813 IkReal x424=((cj3)*(cj5));
1814 IkReal x425=((r02)*(sj7));
1815 IkReal x426=((cj5)*(sj7));
1816 IkReal x427=((cj3)*(sj5));
1817 IkReal x428=((r11)*(sj3));
1818 IkReal x429=((r10)*(sj3));
1819 IkReal x430=((r12)*(sj3));
1820 IkReal x431=((sj5)*(sj7));
1821 IkReal x432=((cj7)*(cj8)*(sj5));
1822 IkReal x433=((IkReal(1.00000000000000))*(cj7)*(sj8));
1823 IkReal x434=((cj5)*(cj7)*(cj8));
1824 if( IKabs(((gconst79)*(((((x429)*(x434)))+(((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x432)))+(((x424)*(x425)))+(((x426)*(x430)))+(((IkReal(-1.00000000000000))*(r01)*(x424)*(x433)))+(((IkReal(-1.00000000000000))*(cj5)*(x428)*(x433)))+(((cj7)*(cj8)*(r00)*(x424)))+(((IkReal(-1.00000000000000))*(r22)*(x431))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst79)*(((((x429)*(x432)))+(((x425)*(x427)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x433)))+(((cj7)*(cj8)*(r00)*(x427)))+(((r22)*(x426)))+(((x430)*(x431)))+(((IkReal(-1.00000000000000))*(sj5)*(x428)*(x433)))+(((r20)*(x434)))+(((IkReal(-1.00000000000000))*(r01)*(x427)*(x433))))))) < IKFAST_ATAN2_MAGTHRESH )
1825  continue;
1826 j4array[0]=IKatan2(((gconst79)*(((((x429)*(x434)))+(((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x432)))+(((x424)*(x425)))+(((x426)*(x430)))+(((IkReal(-1.00000000000000))*(r01)*(x424)*(x433)))+(((IkReal(-1.00000000000000))*(cj5)*(x428)*(x433)))+(((cj7)*(cj8)*(r00)*(x424)))+(((IkReal(-1.00000000000000))*(r22)*(x431)))))), ((gconst79)*(((((x429)*(x432)))+(((x425)*(x427)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x433)))+(((cj7)*(cj8)*(r00)*(x427)))+(((r22)*(x426)))+(((x430)*(x431)))+(((IkReal(-1.00000000000000))*(sj5)*(x428)*(x433)))+(((r20)*(x434)))+(((IkReal(-1.00000000000000))*(r01)*(x427)*(x433)))))));
1827 sj4array[0]=IKsin(j4array[0]);
1828 cj4array[0]=IKcos(j4array[0]);
1829 if( j4array[0] > IKPI )
1830 {
1831  j4array[0]-=IK2PI;
1832 }
1833 else if( j4array[0] < -IKPI )
1834 { j4array[0]+=IK2PI;
1835 }
1836 j4valid[0] = true;
1837 for(int ij4 = 0; ij4 < 1; ++ij4)
1838 {
1839 if( !j4valid[ij4] )
1840 {
1841  continue;
1842 }
1843 _ij4[0] = ij4; _ij4[1] = -1;
1844 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1845 {
1846 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1847 {
1848  j4valid[iij4]=false; _ij4[1] = iij4; break;
1849 }
1850 }
1851 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1852 {
1853 IkReal evalcond[4];
1854 IkReal x435=IKcos(j4);
1855 IkReal x436=IKsin(j4);
1856 IkReal x437=((IkReal(1.00000000000000))*(cj7));
1857 IkReal x438=((cj8)*(r20));
1858 IkReal x439=((cj3)*(r02));
1859 IkReal x440=((IkReal(1.00000000000000))*(sj7));
1860 IkReal x441=((sj3)*(sj7));
1861 IkReal x442=((r21)*(sj8));
1862 IkReal x443=((IkReal(1.00000000000000))*(cj5));
1863 IkReal x444=((cj8)*(r10));
1864 IkReal x445=((sj5)*(x436));
1865 IkReal x446=((sj5)*(x435));
1866 IkReal x447=((r11)*(sj3)*(sj8));
1867 IkReal x448=((cj3)*(cj8)*(r00));
1868 IkReal x449=((cj3)*(r01)*(sj8));
1869 IkReal x450=((x435)*(x443));
1870 evalcond[0]=((((IkReal(-1.00000000000000))*(x437)*(x438)))+(((cj7)*(x442)))+(((IkReal(-1.00000000000000))*(x450)))+(x445)+(((IkReal(-1.00000000000000))*(r22)*(x440))));
1871 evalcond[1]=((((IkReal(-1.00000000000000))*(x438)*(x440)))+(((IkReal(-1.00000000000000))*(x446)))+(((sj7)*(x442)))+(((IkReal(-1.00000000000000))*(x436)*(x443)))+(((cj7)*(r22))));
1872 evalcond[2]=((((IkReal(-1.00000000000000))*(x437)*(x447)))+(((IkReal(-1.00000000000000))*(x437)*(x449)))+(((sj7)*(x439)))+(((cj5)*(x436)))+(((cj7)*(sj3)*(x444)))+(((cj7)*(x448)))+(x446)+(((r12)*(x441))));
1873 evalcond[3]=((((IkReal(-1.00000000000000))*(x437)*(x439)))+(((sj7)*(x448)))+(((IkReal(-1.00000000000000))*(x450)))+(((x441)*(x444)))+(x445)+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x437)))+(((IkReal(-1.00000000000000))*(x440)*(x447)))+(((IkReal(-1.00000000000000))*(x440)*(x449))));
1874 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
1875 {
1876 continue;
1877 }
1878 }
1879 
1880 {
1881 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1882 vinfos[0].jointtype = 1;
1883 vinfos[0].foffset = j3;
1884 vinfos[0].indices[0] = _ij3[0];
1885 vinfos[0].indices[1] = _ij3[1];
1886 vinfos[0].maxsolutions = _nj3;
1887 vinfos[1].jointtype = 1;
1888 vinfos[1].foffset = j4;
1889 vinfos[1].indices[0] = _ij4[0];
1890 vinfos[1].indices[1] = _ij4[1];
1891 vinfos[1].maxsolutions = _nj4;
1892 vinfos[2].jointtype = 1;
1893 vinfos[2].foffset = j5;
1894 vinfos[2].indices[0] = _ij5[0];
1895 vinfos[2].indices[1] = _ij5[1];
1896 vinfos[2].maxsolutions = _nj5;
1897 vinfos[3].jointtype = 1;
1898 vinfos[3].foffset = j6;
1899 vinfos[3].indices[0] = _ij6[0];
1900 vinfos[3].indices[1] = _ij6[1];
1901 vinfos[3].maxsolutions = _nj6;
1902 vinfos[4].jointtype = 1;
1903 vinfos[4].foffset = j7;
1904 vinfos[4].indices[0] = _ij7[0];
1905 vinfos[4].indices[1] = _ij7[1];
1906 vinfos[4].maxsolutions = _nj7;
1907 vinfos[5].jointtype = 1;
1908 vinfos[5].foffset = j8;
1909 vinfos[5].indices[0] = _ij8[0];
1910 vinfos[5].indices[1] = _ij8[1];
1911 vinfos[5].maxsolutions = _nj8;
1912 std::vector<int> vfree(0);
1913 solutions.AddSolution(vinfos,vfree);
1914 }
1915 }
1916 }
1917 
1918 }
1919 
1920 }
1921 
1922 } else
1923 {
1924 {
1925 IkReal j4array[1], cj4array[1], sj4array[1];
1926 bool j4valid[1]={false};
1927 _nj4 = 1;
1928 IkReal x451=((cj7)*(sj5));
1929 IkReal x452=((r21)*(sj8));
1930 IkReal x453=((cj5)*(cj7));
1931 IkReal x454=((cj8)*(r20));
1932 IkReal x455=((sj5)*(sj7));
1933 IkReal x456=((IkReal(1.00000000000000))*(cj5)*(sj7));
1934 if( IKabs(((gconst78)*(((((IkReal(-1.00000000000000))*(x454)*(x456)))+(((x451)*(x454)))+(((r22)*(x455)))+(((r22)*(x453)))+(((IkReal(-1.00000000000000))*(x451)*(x452)))+(((cj5)*(sj7)*(x452))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst78)*(((((x452)*(x453)))+(((x452)*(x455)))+(((IkReal(-1.00000000000000))*(x453)*(x454)))+(((IkReal(-1.00000000000000))*(r22)*(x456)))+(((IkReal(-1.00000000000000))*(x454)*(x455)))+(((r22)*(x451))))))) < IKFAST_ATAN2_MAGTHRESH )
1935  continue;
1936 j4array[0]=IKatan2(((gconst78)*(((((IkReal(-1.00000000000000))*(x454)*(x456)))+(((x451)*(x454)))+(((r22)*(x455)))+(((r22)*(x453)))+(((IkReal(-1.00000000000000))*(x451)*(x452)))+(((cj5)*(sj7)*(x452)))))), ((gconst78)*(((((x452)*(x453)))+(((x452)*(x455)))+(((IkReal(-1.00000000000000))*(x453)*(x454)))+(((IkReal(-1.00000000000000))*(r22)*(x456)))+(((IkReal(-1.00000000000000))*(x454)*(x455)))+(((r22)*(x451)))))));
1937 sj4array[0]=IKsin(j4array[0]);
1938 cj4array[0]=IKcos(j4array[0]);
1939 if( j4array[0] > IKPI )
1940 {
1941  j4array[0]-=IK2PI;
1942 }
1943 else if( j4array[0] < -IKPI )
1944 { j4array[0]+=IK2PI;
1945 }
1946 j4valid[0] = true;
1947 for(int ij4 = 0; ij4 < 1; ++ij4)
1948 {
1949 if( !j4valid[ij4] )
1950 {
1951  continue;
1952 }
1953 _ij4[0] = ij4; _ij4[1] = -1;
1954 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1955 {
1956 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1957 {
1958  j4valid[iij4]=false; _ij4[1] = iij4; break;
1959 }
1960 }
1961 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1962 {
1963 IkReal evalcond[4];
1964 IkReal x457=IKcos(j4);
1965 IkReal x458=IKsin(j4);
1966 IkReal x459=((IkReal(1.00000000000000))*(cj7));
1967 IkReal x460=((cj8)*(r20));
1968 IkReal x461=((cj3)*(r02));
1969 IkReal x462=((IkReal(1.00000000000000))*(sj7));
1970 IkReal x463=((sj3)*(sj7));
1971 IkReal x464=((r21)*(sj8));
1972 IkReal x465=((IkReal(1.00000000000000))*(cj5));
1973 IkReal x466=((cj8)*(r10));
1974 IkReal x467=((sj5)*(x458));
1975 IkReal x468=((sj5)*(x457));
1976 IkReal x469=((r11)*(sj3)*(sj8));
1977 IkReal x470=((cj3)*(cj8)*(r00));
1978 IkReal x471=((cj3)*(r01)*(sj8));
1979 IkReal x472=((x457)*(x465));
1980 evalcond[0]=((((IkReal(-1.00000000000000))*(x472)))+(((IkReal(-1.00000000000000))*(x459)*(x460)))+(x467)+(((IkReal(-1.00000000000000))*(r22)*(x462)))+(((cj7)*(x464))));
1981 evalcond[1]=((((sj7)*(x464)))+(((IkReal(-1.00000000000000))*(x460)*(x462)))+(((IkReal(-1.00000000000000))*(x468)))+(((IkReal(-1.00000000000000))*(x458)*(x465)))+(((cj7)*(r22))));
1982 evalcond[2]=((((cj5)*(x458)))+(((IkReal(-1.00000000000000))*(x459)*(x471)))+(((sj7)*(x461)))+(((IkReal(-1.00000000000000))*(x459)*(x469)))+(((cj7)*(sj3)*(x466)))+(((r12)*(x463)))+(x468)+(((cj7)*(x470))));
1983 evalcond[3]=((((IkReal(-1.00000000000000))*(x462)*(x471)))+(((IkReal(-1.00000000000000))*(x462)*(x469)))+(((x463)*(x466)))+(((IkReal(-1.00000000000000))*(x472)))+(((IkReal(-1.00000000000000))*(x459)*(x461)))+(x467)+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x459)))+(((sj7)*(x470))));
1984 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
1985 {
1986 continue;
1987 }
1988 }
1989 
1990 {
1991 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1992 vinfos[0].jointtype = 1;
1993 vinfos[0].foffset = j3;
1994 vinfos[0].indices[0] = _ij3[0];
1995 vinfos[0].indices[1] = _ij3[1];
1996 vinfos[0].maxsolutions = _nj3;
1997 vinfos[1].jointtype = 1;
1998 vinfos[1].foffset = j4;
1999 vinfos[1].indices[0] = _ij4[0];
2000 vinfos[1].indices[1] = _ij4[1];
2001 vinfos[1].maxsolutions = _nj4;
2002 vinfos[2].jointtype = 1;
2003 vinfos[2].foffset = j5;
2004 vinfos[2].indices[0] = _ij5[0];
2005 vinfos[2].indices[1] = _ij5[1];
2006 vinfos[2].maxsolutions = _nj5;
2007 vinfos[3].jointtype = 1;
2008 vinfos[3].foffset = j6;
2009 vinfos[3].indices[0] = _ij6[0];
2010 vinfos[3].indices[1] = _ij6[1];
2011 vinfos[3].maxsolutions = _nj6;
2012 vinfos[4].jointtype = 1;
2013 vinfos[4].foffset = j7;
2014 vinfos[4].indices[0] = _ij7[0];
2015 vinfos[4].indices[1] = _ij7[1];
2016 vinfos[4].maxsolutions = _nj7;
2017 vinfos[5].jointtype = 1;
2018 vinfos[5].foffset = j8;
2019 vinfos[5].indices[0] = _ij8[0];
2020 vinfos[5].indices[1] = _ij8[1];
2021 vinfos[5].maxsolutions = _nj8;
2022 std::vector<int> vfree(0);
2023 solutions.AddSolution(vinfos,vfree);
2024 }
2025 }
2026 }
2027 
2028 }
2029 
2030 }
2031 }
2032 }
2033 
2034 }
2035 
2036 }
2037 
2038 } else
2039 {
2040 {
2041 IkReal j4array[1], cj4array[1], sj4array[1];
2042 bool j4valid[1]={false};
2043 _nj4 = 1;
2044 IkReal x473=((cj7)*(sj5));
2045 IkReal x474=((r21)*(sj8));
2046 IkReal x475=((cj5)*(cj7));
2047 IkReal x476=((cj8)*(r20));
2048 IkReal x477=((sj5)*(sj7));
2049 IkReal x478=((IkReal(1.00000000000000))*(cj5)*(sj7));
2050 if( IKabs(((gconst77)*(((((x473)*(x476)))+(((IkReal(-1.00000000000000))*(x476)*(x478)))+(((r22)*(x475)))+(((r22)*(x477)))+(((IkReal(-1.00000000000000))*(x473)*(x474)))+(((cj5)*(sj7)*(x474))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst77)*(((((IkReal(-1.00000000000000))*(x475)*(x476)))+(((IkReal(-1.00000000000000))*(x476)*(x477)))+(((IkReal(-1.00000000000000))*(r22)*(x478)))+(((x474)*(x477)))+(((x474)*(x475)))+(((r22)*(x473))))))) < IKFAST_ATAN2_MAGTHRESH )
2051  continue;
2052 j4array[0]=IKatan2(((gconst77)*(((((x473)*(x476)))+(((IkReal(-1.00000000000000))*(x476)*(x478)))+(((r22)*(x475)))+(((r22)*(x477)))+(((IkReal(-1.00000000000000))*(x473)*(x474)))+(((cj5)*(sj7)*(x474)))))), ((gconst77)*(((((IkReal(-1.00000000000000))*(x475)*(x476)))+(((IkReal(-1.00000000000000))*(x476)*(x477)))+(((IkReal(-1.00000000000000))*(r22)*(x478)))+(((x474)*(x477)))+(((x474)*(x475)))+(((r22)*(x473)))))));
2053 sj4array[0]=IKsin(j4array[0]);
2054 cj4array[0]=IKcos(j4array[0]);
2055 if( j4array[0] > IKPI )
2056 {
2057  j4array[0]-=IK2PI;
2058 }
2059 else if( j4array[0] < -IKPI )
2060 { j4array[0]+=IK2PI;
2061 }
2062 j4valid[0] = true;
2063 for(int ij4 = 0; ij4 < 1; ++ij4)
2064 {
2065 if( !j4valid[ij4] )
2066 {
2067  continue;
2068 }
2069 _ij4[0] = ij4; _ij4[1] = -1;
2070 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
2071 {
2072 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
2073 {
2074  j4valid[iij4]=false; _ij4[1] = iij4; break;
2075 }
2076 }
2077 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
2078 {
2079 IkReal evalcond[2];
2080 IkReal x479=IKcos(j4);
2081 IkReal x480=IKsin(j4);
2082 IkReal x481=((IkReal(1.00000000000000))*(cj5));
2083 IkReal x482=((r21)*(sj8));
2084 IkReal x483=((IkReal(1.00000000000000))*(cj8)*(r20));
2085 evalcond[0]=((((cj7)*(x482)))+(((IkReal(-1.00000000000000))*(x479)*(x481)))+(((sj5)*(x480)))+(((IkReal(-1.00000000000000))*(cj7)*(x483)))+(((IkReal(-1.00000000000000))*(r22)*(sj7))));
2086 evalcond[1]=((((sj7)*(x482)))+(((IkReal(-1.00000000000000))*(sj5)*(x479)))+(((IkReal(-1.00000000000000))*(sj7)*(x483)))+(((IkReal(-1.00000000000000))*(x480)*(x481)))+(((cj7)*(r22))));
2087 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
2088 {
2089 continue;
2090 }
2091 }
2092 
2093 {
2094 IkReal dummyeval[1];
2095 IkReal gconst80;
2096 IkReal x484=(cj8)*(cj8);
2097 IkReal x485=(sj8)*(sj8);
2098 IkReal x486=((IkReal(2.00000000000000))*(cj8)*(sj8));
2099 IkReal x487=((IkReal(1.00000000000000))*(x484));
2100 IkReal x488=((IkReal(1.00000000000000))*(x485));
2101 gconst80=IKsign(((((IkReal(-1.00000000000000))*(r10)*(r11)*(x486)))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x486)))+(((IkReal(-1.00000000000000))*(x487)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x487)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x488)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x488)*((r10)*(r10))))));
2102 IkReal x489=(cj8)*(cj8);
2103 IkReal x490=(sj8)*(sj8);
2104 IkReal x491=((IkReal(2.00000000000000))*(cj8)*(sj8));
2105 IkReal x492=((IkReal(1.00000000000000))*(x489));
2106 IkReal x493=((IkReal(1.00000000000000))*(x490));
2107 dummyeval[0]=((((IkReal(-1.00000000000000))*(x493)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x492)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x491)))+(((IkReal(-1.00000000000000))*(x493)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x491)))+(((IkReal(-1.00000000000000))*(x492)*((r11)*(r11)))));
2108 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2109 {
2110 {
2111 IkReal dummyeval[1];
2112 IkReal gconst81;
2113 IkReal x494=(sj8)*(sj8);
2114 IkReal x495=(cj8)*(cj8);
2115 IkReal x496=((sj7)*(sj8));
2116 IkReal x497=((IkReal(1.00000000000000))*(r02));
2117 IkReal x498=((r01)*(r10));
2118 IkReal x499=((cj8)*(sj7));
2119 IkReal x500=((cj7)*(x494));
2120 IkReal x501=((IkReal(1.00000000000000))*(r00)*(r11));
2121 IkReal x502=((cj7)*(x495));
2122 gconst81=IKsign(((((IkReal(-1.00000000000000))*(x501)*(x502)))+(((r00)*(r12)*(x496)))+(((x498)*(x502)))+(((x498)*(x500)))+(((IkReal(-1.00000000000000))*(r11)*(x497)*(x499)))+(((IkReal(-1.00000000000000))*(r10)*(x496)*(x497)))+(((IkReal(-1.00000000000000))*(x500)*(x501)))+(((r01)*(r12)*(x499)))));
2123 IkReal x503=(sj8)*(sj8);
2124 IkReal x504=(cj8)*(cj8);
2125 IkReal x505=((sj7)*(sj8));
2126 IkReal x506=((IkReal(1.00000000000000))*(r02));
2127 IkReal x507=((r01)*(r10));
2128 IkReal x508=((cj8)*(sj7));
2129 IkReal x509=((cj7)*(x503));
2130 IkReal x510=((IkReal(1.00000000000000))*(r00)*(r11));
2131 IkReal x511=((cj7)*(x504));
2132 dummyeval[0]=((((IkReal(-1.00000000000000))*(r11)*(x506)*(x508)))+(((x507)*(x511)))+(((x507)*(x509)))+(((r01)*(r12)*(x508)))+(((IkReal(-1.00000000000000))*(x509)*(x510)))+(((IkReal(-1.00000000000000))*(x510)*(x511)))+(((r00)*(r12)*(x505)))+(((IkReal(-1.00000000000000))*(r10)*(x505)*(x506))));
2133 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2134 {
2135 continue;
2136 
2137 } else
2138 {
2139 {
2140 IkReal j3array[1], cj3array[1], sj3array[1];
2141 bool j3valid[1]={false};
2142 _nj3 = 1;
2143 IkReal x512=((cj7)*(cj8));
2144 IkReal x513=((IkReal(1.00000000000000))*(cj7)*(sj8));
2145 if( IKabs(((gconst81)*(((((IkReal(-1.00000000000000))*(r11)*(x513)))+(((r10)*(x512)))+(((r12)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst81)*(((((IkReal(-1.00000000000000))*(r01)*(x513)))+(((r02)*(sj7)))+(((r00)*(x512))))))) < IKFAST_ATAN2_MAGTHRESH )
2146  continue;
2147 j3array[0]=IKatan2(((gconst81)*(((((IkReal(-1.00000000000000))*(r11)*(x513)))+(((r10)*(x512)))+(((r12)*(sj7)))))), ((gconst81)*(((((IkReal(-1.00000000000000))*(r01)*(x513)))+(((r02)*(sj7)))+(((r00)*(x512)))))));
2148 sj3array[0]=IKsin(j3array[0]);
2149 cj3array[0]=IKcos(j3array[0]);
2150 if( j3array[0] > IKPI )
2151 {
2152  j3array[0]-=IK2PI;
2153 }
2154 else if( j3array[0] < -IKPI )
2155 { j3array[0]+=IK2PI;
2156 }
2157 j3valid[0] = true;
2158 for(int ij3 = 0; ij3 < 1; ++ij3)
2159 {
2160 if( !j3valid[ij3] )
2161 {
2162  continue;
2163 }
2164 _ij3[0] = ij3; _ij3[1] = -1;
2165 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2166 {
2167 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2168 {
2169  j3valid[iij3]=false; _ij3[1] = iij3; break;
2170 }
2171 }
2172 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2173 {
2174 IkReal evalcond[6];
2175 IkReal x514=IKsin(j3);
2176 IkReal x515=IKcos(j3);
2177 IkReal x516=((r01)*(sj8));
2178 IkReal x517=((cj8)*(r00));
2179 IkReal x518=((r00)*(sj8));
2180 IkReal x519=((cj8)*(r11));
2181 IkReal x520=((r11)*(sj8));
2182 IkReal x521=((r10)*(sj8));
2183 IkReal x522=((cj8)*(r10));
2184 IkReal x523=((cj7)*(x514));
2185 IkReal x524=((sj7)*(x515));
2186 IkReal x525=((IkReal(1.00000000000000))*(x514));
2187 IkReal x526=((IkReal(1.00000000000000))*(x515));
2188 IkReal x527=((cj8)*(x514));
2189 IkReal x528=((IkReal(1.00000000000000))*(x520));
2190 IkReal x529=((sj7)*(x514));
2191 IkReal x530=((cj7)*(x515));
2192 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x521)*(x526)))+(((x514)*(x518)))+(((r01)*(x527)))+(((IkReal(-1.00000000000000))*(x519)*(x526))));
2193 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x526)))+(((IkReal(-1.00000000000000))*(x521)*(x525)))+(((IkReal(-1.00000000000000))*(x518)*(x526)))+(((IkReal(-1.00000000000000))*(x519)*(x525))));
2194 evalcond[2]=((((x522)*(x530)))+(((IkReal(-1.00000000000000))*(cj7)*(x520)*(x526)))+(((r12)*(x524)))+(((x516)*(x523)))+(((IkReal(-1.00000000000000))*(x517)*(x523)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x525))));
2195 evalcond[3]=((((x522)*(x524)))+(((IkReal(-1.00000000000000))*(x524)*(x528)))+(((r02)*(x523)))+(((IkReal(-1.00000000000000))*(sj7)*(x517)*(x525)))+(((x516)*(x529)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x526))));
2196 evalcond[4]=((((x522)*(x523)))+(((r02)*(x524)))+(((IkReal(-1.00000000000000))*(x523)*(x528)))+(((r12)*(x529)))+(((cj5)*(sj4)))+(((cj4)*(sj5)))+(((x517)*(x530)))+(((IkReal(-1.00000000000000))*(cj7)*(x516)*(x526))));
2197 evalcond[5]=((((x522)*(x529)))+(((x517)*(x524)))+(((IkReal(-1.00000000000000))*(x516)*(x524)))+(((sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x526)))+(((IkReal(-1.00000000000000))*(r12)*(x523)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(sj7)*(x520)*(x525))));
2198 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
2199 {
2200 continue;
2201 }
2202 }
2203 
2204 {
2205 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2206 vinfos[0].jointtype = 1;
2207 vinfos[0].foffset = j3;
2208 vinfos[0].indices[0] = _ij3[0];
2209 vinfos[0].indices[1] = _ij3[1];
2210 vinfos[0].maxsolutions = _nj3;
2211 vinfos[1].jointtype = 1;
2212 vinfos[1].foffset = j4;
2213 vinfos[1].indices[0] = _ij4[0];
2214 vinfos[1].indices[1] = _ij4[1];
2215 vinfos[1].maxsolutions = _nj4;
2216 vinfos[2].jointtype = 1;
2217 vinfos[2].foffset = j5;
2218 vinfos[2].indices[0] = _ij5[0];
2219 vinfos[2].indices[1] = _ij5[1];
2220 vinfos[2].maxsolutions = _nj5;
2221 vinfos[3].jointtype = 1;
2222 vinfos[3].foffset = j6;
2223 vinfos[3].indices[0] = _ij6[0];
2224 vinfos[3].indices[1] = _ij6[1];
2225 vinfos[3].maxsolutions = _nj6;
2226 vinfos[4].jointtype = 1;
2227 vinfos[4].foffset = j7;
2228 vinfos[4].indices[0] = _ij7[0];
2229 vinfos[4].indices[1] = _ij7[1];
2230 vinfos[4].maxsolutions = _nj7;
2231 vinfos[5].jointtype = 1;
2232 vinfos[5].foffset = j8;
2233 vinfos[5].indices[0] = _ij8[0];
2234 vinfos[5].indices[1] = _ij8[1];
2235 vinfos[5].maxsolutions = _nj8;
2236 std::vector<int> vfree(0);
2237 solutions.AddSolution(vinfos,vfree);
2238 }
2239 }
2240 }
2241 
2242 }
2243 
2244 }
2245 
2246 } else
2247 {
2248 {
2249 IkReal j3array[1], cj3array[1], sj3array[1];
2250 bool j3valid[1]={false};
2251 _nj3 = 1;
2252 if( IKabs(((gconst80)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst80)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
2253  continue;
2254 j3array[0]=IKatan2(((gconst80)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst80)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
2255 sj3array[0]=IKsin(j3array[0]);
2256 cj3array[0]=IKcos(j3array[0]);
2257 if( j3array[0] > IKPI )
2258 {
2259  j3array[0]-=IK2PI;
2260 }
2261 else if( j3array[0] < -IKPI )
2262 { j3array[0]+=IK2PI;
2263 }
2264 j3valid[0] = true;
2265 for(int ij3 = 0; ij3 < 1; ++ij3)
2266 {
2267 if( !j3valid[ij3] )
2268 {
2269  continue;
2270 }
2271 _ij3[0] = ij3; _ij3[1] = -1;
2272 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2273 {
2274 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2275 {
2276  j3valid[iij3]=false; _ij3[1] = iij3; break;
2277 }
2278 }
2279 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2280 {
2281 IkReal evalcond[6];
2282 IkReal x531=IKsin(j3);
2283 IkReal x532=IKcos(j3);
2284 IkReal x533=((r01)*(sj8));
2285 IkReal x534=((cj8)*(r00));
2286 IkReal x535=((r00)*(sj8));
2287 IkReal x536=((cj8)*(r11));
2288 IkReal x537=((r11)*(sj8));
2289 IkReal x538=((r10)*(sj8));
2290 IkReal x539=((cj8)*(r10));
2291 IkReal x540=((cj7)*(x531));
2292 IkReal x541=((sj7)*(x532));
2293 IkReal x542=((IkReal(1.00000000000000))*(x531));
2294 IkReal x543=((IkReal(1.00000000000000))*(x532));
2295 IkReal x544=((cj8)*(x531));
2296 IkReal x545=((IkReal(1.00000000000000))*(x537));
2297 IkReal x546=((sj7)*(x531));
2298 IkReal x547=((cj7)*(x532));
2299 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x538)*(x543)))+(((x531)*(x535)))+(((IkReal(-1.00000000000000))*(x536)*(x543)))+(((r01)*(x544))));
2300 evalcond[1]=((((IkReal(-1.00000000000000))*(x538)*(x542)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x543)))+(((IkReal(-1.00000000000000))*(x535)*(x543)))+(((IkReal(-1.00000000000000))*(x536)*(x542))));
2301 evalcond[2]=((((x539)*(x547)))+(((IkReal(-1.00000000000000))*(cj7)*(x537)*(x543)))+(((r12)*(x541)))+(((IkReal(-1.00000000000000))*(x534)*(x540)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x542)))+(((x533)*(x540))));
2302 evalcond[3]=((((IkReal(-1.00000000000000))*(x541)*(x545)))+(((x539)*(x541)))+(((r02)*(x540)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x543)))+(((x533)*(x546)))+(((IkReal(-1.00000000000000))*(sj7)*(x534)*(x542))));
2303 evalcond[4]=((((x539)*(x540)))+(((r02)*(x541)))+(((IkReal(-1.00000000000000))*(x540)*(x545)))+(((cj5)*(sj4)))+(((r12)*(x546)))+(((IkReal(-1.00000000000000))*(cj7)*(x533)*(x543)))+(((cj4)*(sj5)))+(((x534)*(x547))));
2304 evalcond[5]=((((x539)*(x546)))+(((IkReal(-1.00000000000000))*(sj7)*(x537)*(x542)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x543)))+(((sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(x533)*(x541)))+(((IkReal(-1.00000000000000))*(r12)*(x540)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)))+(((x534)*(x541))));
2305 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
2306 {
2307 continue;
2308 }
2309 }
2310 
2311 {
2312 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2313 vinfos[0].jointtype = 1;
2314 vinfos[0].foffset = j3;
2315 vinfos[0].indices[0] = _ij3[0];
2316 vinfos[0].indices[1] = _ij3[1];
2317 vinfos[0].maxsolutions = _nj3;
2318 vinfos[1].jointtype = 1;
2319 vinfos[1].foffset = j4;
2320 vinfos[1].indices[0] = _ij4[0];
2321 vinfos[1].indices[1] = _ij4[1];
2322 vinfos[1].maxsolutions = _nj4;
2323 vinfos[2].jointtype = 1;
2324 vinfos[2].foffset = j5;
2325 vinfos[2].indices[0] = _ij5[0];
2326 vinfos[2].indices[1] = _ij5[1];
2327 vinfos[2].maxsolutions = _nj5;
2328 vinfos[3].jointtype = 1;
2329 vinfos[3].foffset = j6;
2330 vinfos[3].indices[0] = _ij6[0];
2331 vinfos[3].indices[1] = _ij6[1];
2332 vinfos[3].maxsolutions = _nj6;
2333 vinfos[4].jointtype = 1;
2334 vinfos[4].foffset = j7;
2335 vinfos[4].indices[0] = _ij7[0];
2336 vinfos[4].indices[1] = _ij7[1];
2337 vinfos[4].maxsolutions = _nj7;
2338 vinfos[5].jointtype = 1;
2339 vinfos[5].foffset = j8;
2340 vinfos[5].indices[0] = _ij8[0];
2341 vinfos[5].indices[1] = _ij8[1];
2342 vinfos[5].maxsolutions = _nj8;
2343 std::vector<int> vfree(0);
2344 solutions.AddSolution(vinfos,vfree);
2345 }
2346 }
2347 }
2348 
2349 }
2350 
2351 }
2352 }
2353 }
2354 
2355 }
2356 
2357 }
2358 
2359 } else
2360 {
2361 {
2362 IkReal j3array[1], cj3array[1], sj3array[1];
2363 bool j3valid[1]={false};
2364 _nj3 = 1;
2365 if( IKabs(((gconst75)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst75)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
2366  continue;
2367 j3array[0]=IKatan2(((gconst75)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst75)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
2368 sj3array[0]=IKsin(j3array[0]);
2369 cj3array[0]=IKcos(j3array[0]);
2370 if( j3array[0] > IKPI )
2371 {
2372  j3array[0]-=IK2PI;
2373 }
2374 else if( j3array[0] < -IKPI )
2375 { j3array[0]+=IK2PI;
2376 }
2377 j3valid[0] = true;
2378 for(int ij3 = 0; ij3 < 1; ++ij3)
2379 {
2380 if( !j3valid[ij3] )
2381 {
2382  continue;
2383 }
2384 _ij3[0] = ij3; _ij3[1] = -1;
2385 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2386 {
2387 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2388 {
2389  j3valid[iij3]=false; _ij3[1] = iij3; break;
2390 }
2391 }
2392 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2393 {
2394 IkReal evalcond[4];
2395 IkReal x548=IKsin(j3);
2396 IkReal x549=IKcos(j3);
2397 IkReal x550=((IkReal(1.00000000000000))*(sj8));
2398 IkReal x551=((IkReal(1.00000000000000))*(cj8));
2399 IkReal x552=((r01)*(sj8));
2400 IkReal x553=((cj8)*(r10));
2401 IkReal x554=((sj7)*(x549));
2402 IkReal x555=((cj7)*(x548));
2403 IkReal x556=((r00)*(x548));
2404 IkReal x557=((sj7)*(x548));
2405 IkReal x558=((cj7)*(x549));
2406 evalcond[0]=((IkReal(-1.00000000000000))+(((sj8)*(x556)))+(((IkReal(-1.00000000000000))*(r11)*(x549)*(x551)))+(((cj8)*(r01)*(x548)))+(((IkReal(-1.00000000000000))*(r10)*(x549)*(x550))));
2407 evalcond[1]=((((IkReal(-1.00000000000000))*(r01)*(x549)*(x551)))+(((IkReal(-1.00000000000000))*(r10)*(x548)*(x550)))+(((IkReal(-1.00000000000000))*(r11)*(x548)*(x551)))+(((IkReal(-1.00000000000000))*(r00)*(x549)*(x550))));
2408 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x557)))+(((r12)*(x554)))+(((IkReal(-1.00000000000000))*(r00)*(x551)*(x555)))+(((IkReal(-1.00000000000000))*(r11)*(x550)*(x558)))+(((x552)*(x555)))+(((x553)*(x558))));
2409 evalcond[3]=((((IkReal(-1.00000000000000))*(sj7)*(x551)*(x556)))+(((r02)*(x555)))+(((IkReal(-1.00000000000000))*(r12)*(x558)))+(((IkReal(-1.00000000000000))*(r11)*(x550)*(x554)))+(((x552)*(x557)))+(((x553)*(x554))));
2410 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
2411 {
2412 continue;
2413 }
2414 }
2415 
2416 {
2417 IkReal dummyeval[1];
2418 IkReal gconst78;
2419 gconst78=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
2420 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
2421 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2422 {
2423 {
2424 IkReal dummyeval[1];
2425 IkReal gconst79;
2426 gconst79=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
2427 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
2428 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2429 {
2430 continue;
2431 
2432 } else
2433 {
2434 {
2435 IkReal j4array[1], cj4array[1], sj4array[1];
2436 bool j4valid[1]={false};
2437 _nj4 = 1;
2438 IkReal x559=((cj3)*(cj5));
2439 IkReal x560=((r02)*(sj7));
2440 IkReal x561=((cj5)*(sj7));
2441 IkReal x562=((cj3)*(sj5));
2442 IkReal x563=((r11)*(sj3));
2443 IkReal x564=((r10)*(sj3));
2444 IkReal x565=((r12)*(sj3));
2445 IkReal x566=((sj5)*(sj7));
2446 IkReal x567=((cj7)*(cj8)*(sj5));
2447 IkReal x568=((IkReal(1.00000000000000))*(cj7)*(sj8));
2448 IkReal x569=((cj5)*(cj7)*(cj8));
2449 if( IKabs(((gconst79)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(cj5)*(x563)*(x568)))+(((x564)*(x569)))+(((cj7)*(cj8)*(r00)*(x559)))+(((IkReal(-1.00000000000000))*(r22)*(x566)))+(((x561)*(x565)))+(((IkReal(-1.00000000000000))*(r20)*(x567)))+(((x559)*(x560)))+(((IkReal(-1.00000000000000))*(r01)*(x559)*(x568))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst79)*(((((x565)*(x566)))+(((x564)*(x567)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x568)))+(((r22)*(x561)))+(((IkReal(-1.00000000000000))*(sj5)*(x563)*(x568)))+(((IkReal(-1.00000000000000))*(r01)*(x562)*(x568)))+(((x560)*(x562)))+(((r20)*(x569)))+(((cj7)*(cj8)*(r00)*(x562))))))) < IKFAST_ATAN2_MAGTHRESH )
2450  continue;
2451 j4array[0]=IKatan2(((gconst79)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(cj5)*(x563)*(x568)))+(((x564)*(x569)))+(((cj7)*(cj8)*(r00)*(x559)))+(((IkReal(-1.00000000000000))*(r22)*(x566)))+(((x561)*(x565)))+(((IkReal(-1.00000000000000))*(r20)*(x567)))+(((x559)*(x560)))+(((IkReal(-1.00000000000000))*(r01)*(x559)*(x568)))))), ((gconst79)*(((((x565)*(x566)))+(((x564)*(x567)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x568)))+(((r22)*(x561)))+(((IkReal(-1.00000000000000))*(sj5)*(x563)*(x568)))+(((IkReal(-1.00000000000000))*(r01)*(x562)*(x568)))+(((x560)*(x562)))+(((r20)*(x569)))+(((cj7)*(cj8)*(r00)*(x562)))))));
2452 sj4array[0]=IKsin(j4array[0]);
2453 cj4array[0]=IKcos(j4array[0]);
2454 if( j4array[0] > IKPI )
2455 {
2456  j4array[0]-=IK2PI;
2457 }
2458 else if( j4array[0] < -IKPI )
2459 { j4array[0]+=IK2PI;
2460 }
2461 j4valid[0] = true;
2462 for(int ij4 = 0; ij4 < 1; ++ij4)
2463 {
2464 if( !j4valid[ij4] )
2465 {
2466  continue;
2467 }
2468 _ij4[0] = ij4; _ij4[1] = -1;
2469 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
2470 {
2471 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
2472 {
2473  j4valid[iij4]=false; _ij4[1] = iij4; break;
2474 }
2475 }
2476 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
2477 {
2478 IkReal evalcond[4];
2479 IkReal x570=IKcos(j4);
2480 IkReal x571=IKsin(j4);
2481 IkReal x572=((IkReal(1.00000000000000))*(cj7));
2482 IkReal x573=((cj8)*(r20));
2483 IkReal x574=((cj3)*(r02));
2484 IkReal x575=((IkReal(1.00000000000000))*(sj7));
2485 IkReal x576=((sj3)*(sj7));
2486 IkReal x577=((r21)*(sj8));
2487 IkReal x578=((IkReal(1.00000000000000))*(cj5));
2488 IkReal x579=((cj8)*(r10));
2489 IkReal x580=((sj5)*(x571));
2490 IkReal x581=((sj5)*(x570));
2491 IkReal x582=((r11)*(sj3)*(sj8));
2492 IkReal x583=((cj3)*(cj8)*(r00));
2493 IkReal x584=((cj3)*(r01)*(sj8));
2494 IkReal x585=((x570)*(x578));
2495 evalcond[0]=((((cj7)*(x577)))+(x580)+(((IkReal(-1.00000000000000))*(r22)*(x575)))+(((IkReal(-1.00000000000000))*(x585)))+(((IkReal(-1.00000000000000))*(x572)*(x573))));
2496 evalcond[1]=((((IkReal(-1.00000000000000))*(x581)))+(((IkReal(-1.00000000000000))*(x573)*(x575)))+(((IkReal(-1.00000000000000))*(x571)*(x578)))+(((sj7)*(x577)))+(((cj7)*(r22))));
2497 evalcond[2]=((((cj5)*(x571)))+(((r12)*(x576)))+(((IkReal(-1.00000000000000))*(x572)*(x582)))+(((IkReal(-1.00000000000000))*(x572)*(x584)))+(((cj7)*(x583)))+(((cj7)*(sj3)*(x579)))+(((sj7)*(x574)))+(x581));
2498 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj3)*(x572)))+(((x576)*(x579)))+(x580)+(((IkReal(-1.00000000000000))*(x575)*(x582)))+(((IkReal(-1.00000000000000))*(x575)*(x584)))+(((IkReal(-1.00000000000000))*(x585)))+(((IkReal(-1.00000000000000))*(x572)*(x574)))+(((sj7)*(x583))));
2499 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
2500 {
2501 continue;
2502 }
2503 }
2504 
2505 {
2506 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2507 vinfos[0].jointtype = 1;
2508 vinfos[0].foffset = j3;
2509 vinfos[0].indices[0] = _ij3[0];
2510 vinfos[0].indices[1] = _ij3[1];
2511 vinfos[0].maxsolutions = _nj3;
2512 vinfos[1].jointtype = 1;
2513 vinfos[1].foffset = j4;
2514 vinfos[1].indices[0] = _ij4[0];
2515 vinfos[1].indices[1] = _ij4[1];
2516 vinfos[1].maxsolutions = _nj4;
2517 vinfos[2].jointtype = 1;
2518 vinfos[2].foffset = j5;
2519 vinfos[2].indices[0] = _ij5[0];
2520 vinfos[2].indices[1] = _ij5[1];
2521 vinfos[2].maxsolutions = _nj5;
2522 vinfos[3].jointtype = 1;
2523 vinfos[3].foffset = j6;
2524 vinfos[3].indices[0] = _ij6[0];
2525 vinfos[3].indices[1] = _ij6[1];
2526 vinfos[3].maxsolutions = _nj6;
2527 vinfos[4].jointtype = 1;
2528 vinfos[4].foffset = j7;
2529 vinfos[4].indices[0] = _ij7[0];
2530 vinfos[4].indices[1] = _ij7[1];
2531 vinfos[4].maxsolutions = _nj7;
2532 vinfos[5].jointtype = 1;
2533 vinfos[5].foffset = j8;
2534 vinfos[5].indices[0] = _ij8[0];
2535 vinfos[5].indices[1] = _ij8[1];
2536 vinfos[5].maxsolutions = _nj8;
2537 std::vector<int> vfree(0);
2538 solutions.AddSolution(vinfos,vfree);
2539 }
2540 }
2541 }
2542 
2543 }
2544 
2545 }
2546 
2547 } else
2548 {
2549 {
2550 IkReal j4array[1], cj4array[1], sj4array[1];
2551 bool j4valid[1]={false};
2552 _nj4 = 1;
2553 IkReal x586=((cj7)*(sj5));
2554 IkReal x587=((r21)*(sj8));
2555 IkReal x588=((cj5)*(cj7));
2556 IkReal x589=((cj8)*(r20));
2557 IkReal x590=((sj5)*(sj7));
2558 IkReal x591=((IkReal(1.00000000000000))*(cj5)*(sj7));
2559 if( IKabs(((gconst78)*(((((r22)*(x590)))+(((IkReal(-1.00000000000000))*(x589)*(x591)))+(((x586)*(x589)))+(((r22)*(x588)))+(((IkReal(-1.00000000000000))*(x586)*(x587)))+(((cj5)*(sj7)*(x587))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst78)*(((((IkReal(-1.00000000000000))*(x588)*(x589)))+(((IkReal(-1.00000000000000))*(x589)*(x590)))+(((x587)*(x588)))+(((IkReal(-1.00000000000000))*(r22)*(x591)))+(((r22)*(x586)))+(((x587)*(x590))))))) < IKFAST_ATAN2_MAGTHRESH )
2560  continue;
2561 j4array[0]=IKatan2(((gconst78)*(((((r22)*(x590)))+(((IkReal(-1.00000000000000))*(x589)*(x591)))+(((x586)*(x589)))+(((r22)*(x588)))+(((IkReal(-1.00000000000000))*(x586)*(x587)))+(((cj5)*(sj7)*(x587)))))), ((gconst78)*(((((IkReal(-1.00000000000000))*(x588)*(x589)))+(((IkReal(-1.00000000000000))*(x589)*(x590)))+(((x587)*(x588)))+(((IkReal(-1.00000000000000))*(r22)*(x591)))+(((r22)*(x586)))+(((x587)*(x590)))))));
2562 sj4array[0]=IKsin(j4array[0]);
2563 cj4array[0]=IKcos(j4array[0]);
2564 if( j4array[0] > IKPI )
2565 {
2566  j4array[0]-=IK2PI;
2567 }
2568 else if( j4array[0] < -IKPI )
2569 { j4array[0]+=IK2PI;
2570 }
2571 j4valid[0] = true;
2572 for(int ij4 = 0; ij4 < 1; ++ij4)
2573 {
2574 if( !j4valid[ij4] )
2575 {
2576  continue;
2577 }
2578 _ij4[0] = ij4; _ij4[1] = -1;
2579 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
2580 {
2581 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
2582 {
2583  j4valid[iij4]=false; _ij4[1] = iij4; break;
2584 }
2585 }
2586 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
2587 {
2588 IkReal evalcond[4];
2589 IkReal x592=IKcos(j4);
2590 IkReal x593=IKsin(j4);
2591 IkReal x594=((IkReal(1.00000000000000))*(cj7));
2592 IkReal x595=((cj8)*(r20));
2593 IkReal x596=((cj3)*(r02));
2594 IkReal x597=((IkReal(1.00000000000000))*(sj7));
2595 IkReal x598=((sj3)*(sj7));
2596 IkReal x599=((r21)*(sj8));
2597 IkReal x600=((IkReal(1.00000000000000))*(cj5));
2598 IkReal x601=((cj8)*(r10));
2599 IkReal x602=((sj5)*(x593));
2600 IkReal x603=((sj5)*(x592));
2601 IkReal x604=((r11)*(sj3)*(sj8));
2602 IkReal x605=((cj3)*(cj8)*(r00));
2603 IkReal x606=((cj3)*(r01)*(sj8));
2604 IkReal x607=((x592)*(x600));
2605 evalcond[0]=((((IkReal(-1.00000000000000))*(x594)*(x595)))+(((IkReal(-1.00000000000000))*(r22)*(x597)))+(x602)+(((IkReal(-1.00000000000000))*(x607)))+(((cj7)*(x599))));
2606 evalcond[1]=((((IkReal(-1.00000000000000))*(x593)*(x600)))+(((sj7)*(x599)))+(((IkReal(-1.00000000000000))*(x603)))+(((IkReal(-1.00000000000000))*(x595)*(x597)))+(((cj7)*(r22))));
2607 evalcond[2]=((((cj7)*(x605)))+(((cj7)*(sj3)*(x601)))+(((sj7)*(x596)))+(((r12)*(x598)))+(x603)+(((IkReal(-1.00000000000000))*(x594)*(x606)))+(((IkReal(-1.00000000000000))*(x594)*(x604)))+(((cj5)*(x593))));
2608 evalcond[3]=((((sj7)*(x605)))+(((IkReal(-1.00000000000000))*(x597)*(x606)))+(((IkReal(-1.00000000000000))*(x597)*(x604)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x594)))+(((IkReal(-1.00000000000000))*(x594)*(x596)))+(x602)+(((IkReal(-1.00000000000000))*(x607)))+(((x598)*(x601))));
2609 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
2610 {
2611 continue;
2612 }
2613 }
2614 
2615 {
2616 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2617 vinfos[0].jointtype = 1;
2618 vinfos[0].foffset = j3;
2619 vinfos[0].indices[0] = _ij3[0];
2620 vinfos[0].indices[1] = _ij3[1];
2621 vinfos[0].maxsolutions = _nj3;
2622 vinfos[1].jointtype = 1;
2623 vinfos[1].foffset = j4;
2624 vinfos[1].indices[0] = _ij4[0];
2625 vinfos[1].indices[1] = _ij4[1];
2626 vinfos[1].maxsolutions = _nj4;
2627 vinfos[2].jointtype = 1;
2628 vinfos[2].foffset = j5;
2629 vinfos[2].indices[0] = _ij5[0];
2630 vinfos[2].indices[1] = _ij5[1];
2631 vinfos[2].maxsolutions = _nj5;
2632 vinfos[3].jointtype = 1;
2633 vinfos[3].foffset = j6;
2634 vinfos[3].indices[0] = _ij6[0];
2635 vinfos[3].indices[1] = _ij6[1];
2636 vinfos[3].maxsolutions = _nj6;
2637 vinfos[4].jointtype = 1;
2638 vinfos[4].foffset = j7;
2639 vinfos[4].indices[0] = _ij7[0];
2640 vinfos[4].indices[1] = _ij7[1];
2641 vinfos[4].maxsolutions = _nj7;
2642 vinfos[5].jointtype = 1;
2643 vinfos[5].foffset = j8;
2644 vinfos[5].indices[0] = _ij8[0];
2645 vinfos[5].indices[1] = _ij8[1];
2646 vinfos[5].maxsolutions = _nj8;
2647 std::vector<int> vfree(0);
2648 solutions.AddSolution(vinfos,vfree);
2649 }
2650 }
2651 }
2652 
2653 }
2654 
2655 }
2656 }
2657 }
2658 
2659 }
2660 
2661 }
2662 }
2663 }
2664 
2665 } else
2666 {
2667 if( 1 )
2668 {
2669 continue;
2670 
2671 } else
2672 {
2673 }
2674 }
2675 }
2676 }
2677 
2678 } else
2679 {
2680 {
2681 IkReal j5array[1], cj5array[1], sj5array[1];
2682 bool j5valid[1]={false};
2683 _nj5 = 1;
2684 IkReal x608=((IkReal(4.00000000000000))*(npx));
2685 IkReal x609=((IkReal(4.00000000000000))*(npy));
2686 if( IKabs(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(-1.00000000000000))*(cj8)*(x609)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(sj8)*(x608))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x609)))+(((cj7)*(cj8)*(x608)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(-1.00000000000000))*(cj8)*(x609)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(sj8)*(x608)))))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x609)))+(((cj7)*(cj8)*(x608)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
2687  continue;
2688 j5array[0]=IKatan2(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(-1.00000000000000))*(cj8)*(x609)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(sj8)*(x608)))))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x609)))+(((cj7)*(cj8)*(x608)))+(((IkReal(-0.360000000000000))*(cj7)))));
2689 sj5array[0]=IKsin(j5array[0]);
2690 cj5array[0]=IKcos(j5array[0]);
2691 if( j5array[0] > IKPI )
2692 {
2693  j5array[0]-=IK2PI;
2694 }
2695 else if( j5array[0] < -IKPI )
2696 { j5array[0]+=IK2PI;
2697 }
2698 j5valid[0] = true;
2699 for(int ij5 = 0; ij5 < 1; ++ij5)
2700 {
2701 if( !j5valid[ij5] )
2702 {
2703  continue;
2704 }
2705 _ij5[0] = ij5; _ij5[1] = -1;
2706 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2707 {
2708 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2709 {
2710  j5valid[iij5]=false; _ij5[1] = iij5; break;
2711 }
2712 }
2713 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2714 {
2715 IkReal evalcond[3];
2716 IkReal x610=IKsin(j5);
2717 IkReal x611=((IkReal(1.00000000000000))*(sj7));
2718 IkReal x612=((npy)*(sj8));
2719 IkReal x613=((cj8)*(npx));
2720 IkReal x614=((IkReal(0.250000000000000))*(x610));
2721 evalcond[0]=((((IkReal(-0.0300000000000000))*(sj6)))+(((IkReal(-0.0950000000000000))*(cj6)))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((sj6)*(x614))));
2722 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x613)))+(((IkReal(-1.00000000000000))*(npz)*(x611)))+(((cj7)*(x612)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
2723 evalcond[2]=((((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x611)*(x613)))+(((IkReal(-1.00000000000000))*(cj6)*(x614)))+(((IkReal(0.0300000000000000))*(cj6)))+(((IkReal(-0.0950000000000000))*(sj6)))+(((cj7)*(npz)))+(((sj7)*(x612))));
2724 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
2725 {
2726 continue;
2727 }
2728 }
2729 
2730 {
2731 IkReal dummyeval[1];
2732 IkReal gconst4;
2733 gconst4=IKsign(((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5))))));
2734 dummyeval[0]=((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5)))));
2735 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2736 {
2737 {
2738 IkReal dummyeval[1];
2739 IkReal gconst5;
2740 gconst5=IKsign(((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5))))));
2741 dummyeval[0]=((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5)))));
2742 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2743 {
2744 {
2745 IkReal dummyeval[1];
2746 IkReal gconst2;
2747 IkReal x615=(sj8)*(sj8);
2748 IkReal x616=(cj8)*(cj8);
2749 IkReal x617=((r00)*(r11));
2750 IkReal x618=((r02)*(sj7));
2751 IkReal x619=((cj7)*(x616));
2752 IkReal x620=((IkReal(1.00000000000000))*(r12)*(sj7));
2753 IkReal x621=((IkReal(1.00000000000000))*(r01)*(r10));
2754 IkReal x622=((cj7)*(x615));
2755 gconst2=IKsign(((((cj8)*(r11)*(x618)))+(((IkReal(-1.00000000000000))*(x621)*(x622)))+(((x617)*(x622)))+(((r10)*(sj8)*(x618)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x620)))+(((x617)*(x619)))+(((IkReal(-1.00000000000000))*(x619)*(x621)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x620)))));
2756 IkReal x623=(sj8)*(sj8);
2757 IkReal x624=(cj8)*(cj8);
2758 IkReal x625=((r00)*(r11));
2759 IkReal x626=((r02)*(sj7));
2760 IkReal x627=((cj7)*(x624));
2761 IkReal x628=((IkReal(1.00000000000000))*(r12)*(sj7));
2762 IkReal x629=((IkReal(1.00000000000000))*(r01)*(r10));
2763 IkReal x630=((cj7)*(x623));
2764 dummyeval[0]=((((IkReal(-1.00000000000000))*(x629)*(x630)))+(((x625)*(x630)))+(((cj8)*(r11)*(x626)))+(((x625)*(x627)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x628)))+(((IkReal(-1.00000000000000))*(x627)*(x629)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x628)))+(((r10)*(sj8)*(x626))));
2765 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2766 {
2767 {
2768 IkReal evalcond[5];
2769 IkReal x631=((IkReal(1.00000000000000))*(sj7));
2770 IkReal x632=((npy)*(sj8));
2771 IkReal x633=((cj8)*(npx));
2772 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
2773 evalcond[1]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(sj5))));
2774 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x631)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x633)))+(((IkReal(0.250000000000000))*(cj5)))+(((cj7)*(x632))));
2775 evalcond[3]=((((cj7)*(r22)))+(((r21)*(sj7)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x631))));
2776 evalcond[4]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x631)*(x633)))+(((sj7)*(x632)))+(((cj7)*(npz))));
2777 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 )
2778 {
2779 {
2780 IkReal dummyeval[1];
2781 IkReal gconst20;
2782 gconst20=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
2783 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
2784 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2785 {
2786 {
2787 IkReal dummyeval[1];
2788 IkReal gconst18;
2789 IkReal x634=(cj8)*(cj8);
2790 IkReal x635=(sj8)*(sj8);
2791 IkReal x636=((cj7)*(r02));
2792 IkReal x637=((IkReal(1.00000000000000))*(r00));
2793 IkReal x638=((cj7)*(r12));
2794 IkReal x639=((r01)*(r10));
2795 IkReal x640=((sj7)*(x635));
2796 IkReal x641=((sj7)*(x634));
2797 gconst18=IKsign(((((IkReal(-1.00000000000000))*(sj8)*(x637)*(x638)))+(((x639)*(x641)))+(((x639)*(x640)))+(((IkReal(-1.00000000000000))*(r11)*(x637)*(x640)))+(((IkReal(-1.00000000000000))*(r11)*(x637)*(x641)))+(((cj8)*(r11)*(x636)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x638)))+(((r10)*(sj8)*(x636)))));
2798 IkReal x642=(cj8)*(cj8);
2799 IkReal x643=(sj8)*(sj8);
2800 IkReal x644=((cj7)*(r02));
2801 IkReal x645=((IkReal(1.00000000000000))*(r00));
2802 IkReal x646=((cj7)*(r12));
2803 IkReal x647=((r01)*(r10));
2804 IkReal x648=((sj7)*(x643));
2805 IkReal x649=((sj7)*(x642));
2806 dummyeval[0]=((((IkReal(-1.00000000000000))*(sj8)*(x645)*(x646)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x646)))+(((cj8)*(r11)*(x644)))+(((r10)*(sj8)*(x644)))+(((IkReal(-1.00000000000000))*(r11)*(x645)*(x648)))+(((IkReal(-1.00000000000000))*(r11)*(x645)*(x649)))+(((x647)*(x648)))+(((x647)*(x649))));
2807 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2808 {
2809 {
2810 IkReal dummyeval[1];
2811 IkReal gconst19;
2812 IkReal x650=(sj7)*(sj7);
2813 IkReal x651=(cj7)*(cj7);
2814 IkReal x652=((r02)*(r11));
2815 IkReal x653=((sj8)*(x650));
2816 IkReal x654=((IkReal(1.00000000000000))*(r01)*(r12));
2817 IkReal x655=((cj8)*(r00)*(r12));
2818 IkReal x656=((sj8)*(x651));
2819 IkReal x657=((IkReal(1.00000000000000))*(cj8)*(r02)*(r10));
2820 gconst19=IKsign(((((IkReal(-1.00000000000000))*(x651)*(x657)))+(((x652)*(x653)))+(((x652)*(x656)))+(((x651)*(x655)))+(((IkReal(-1.00000000000000))*(x650)*(x657)))+(((x650)*(x655)))+(((IkReal(-1.00000000000000))*(x653)*(x654)))+(((IkReal(-1.00000000000000))*(x654)*(x656)))));
2821 IkReal x658=(sj7)*(sj7);
2822 IkReal x659=(cj7)*(cj7);
2823 IkReal x660=((r02)*(r11));
2824 IkReal x661=((sj8)*(x658));
2825 IkReal x662=((IkReal(1.00000000000000))*(r01)*(r12));
2826 IkReal x663=((cj8)*(r00)*(r12));
2827 IkReal x664=((sj8)*(x659));
2828 IkReal x665=x657;
2829 dummyeval[0]=((((IkReal(-1.00000000000000))*(x662)*(x664)))+(((IkReal(-1.00000000000000))*(x659)*(x665)))+(((IkReal(-1.00000000000000))*(x661)*(x662)))+(((IkReal(-1.00000000000000))*(x658)*(x665)))+(((x660)*(x661)))+(((x660)*(x664)))+(((x659)*(x663)))+(((x658)*(x663))));
2830 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2831 {
2832 continue;
2833 
2834 } else
2835 {
2836 {
2837 IkReal j3array[1], cj3array[1], sj3array[1];
2838 bool j3valid[1]={false};
2839 _nj3 = 1;
2840 IkReal x666=((cj7)*(cj8));
2841 IkReal x667=((IkReal(1.00000000000000))*(cj7)*(sj8));
2842 if( IKabs(((gconst19)*(((((IkReal(-1.00000000000000))*(r11)*(x667)))+(((r12)*(sj7)))+(((r10)*(x666))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst19)*(((((r00)*(x666)))+(((IkReal(-1.00000000000000))*(r01)*(x667)))+(((r02)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH )
2843  continue;
2844 j3array[0]=IKatan2(((gconst19)*(((((IkReal(-1.00000000000000))*(r11)*(x667)))+(((r12)*(sj7)))+(((r10)*(x666)))))), ((gconst19)*(((((r00)*(x666)))+(((IkReal(-1.00000000000000))*(r01)*(x667)))+(((r02)*(sj7)))))));
2845 sj3array[0]=IKsin(j3array[0]);
2846 cj3array[0]=IKcos(j3array[0]);
2847 if( j3array[0] > IKPI )
2848 {
2849  j3array[0]-=IK2PI;
2850 }
2851 else if( j3array[0] < -IKPI )
2852 { j3array[0]+=IK2PI;
2853 }
2854 j3valid[0] = true;
2855 for(int ij3 = 0; ij3 < 1; ++ij3)
2856 {
2857 if( !j3valid[ij3] )
2858 {
2859  continue;
2860 }
2861 _ij3[0] = ij3; _ij3[1] = -1;
2862 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2863 {
2864 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2865 {
2866  j3valid[iij3]=false; _ij3[1] = iij3; break;
2867 }
2868 }
2869 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2870 {
2871 IkReal evalcond[4];
2872 IkReal x668=IKsin(j3);
2873 IkReal x669=IKcos(j3);
2874 IkReal x670=((r01)*(sj8));
2875 IkReal x671=((cj8)*(sj7));
2876 IkReal x672=((IkReal(1.00000000000000))*(sj7));
2877 IkReal x673=((IkReal(1.00000000000000))*(r12));
2878 IkReal x674=((r11)*(sj8));
2879 IkReal x675=((IkReal(1.00000000000000))*(r00));
2880 IkReal x676=((cj7)*(x668));
2881 IkReal x677=((r10)*(x669));
2882 IkReal x678=((IkReal(1.00000000000000))*(cj7)*(x669));
2883 evalcond[0]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x669)))+(((r00)*(sj8)*(x668)))+(((cj8)*(r01)*(x668)))+(((IkReal(-1.00000000000000))*(sj8)*(x677))));
2884 evalcond[1]=((((cj7)*(cj8)*(x677)))+(((IkReal(-1.00000000000000))*(cj8)*(x675)*(x676)))+(((IkReal(-1.00000000000000))*(r02)*(x668)*(x672)))+(((x670)*(x676)))+(((r12)*(sj7)*(x669)))+(((IkReal(-1.00000000000000))*(x674)*(x678))));
2885 evalcond[2]=((IkReal(1.00000000000000))+(((r02)*(x676)))+(((x671)*(x677)))+(((IkReal(-1.00000000000000))*(cj7)*(x669)*(x673)))+(((sj7)*(x668)*(x670)))+(((IkReal(-1.00000000000000))*(x669)*(x672)*(x674)))+(((IkReal(-1.00000000000000))*(x668)*(x671)*(x675))));
2886 evalcond[3]=((((IkReal(-1.00000000000000))*(r02)*(x678)))+(((IkReal(-1.00000000000000))*(x669)*(x670)*(x672)))+(((r00)*(x669)*(x671)))+(((r10)*(x668)*(x671)))+(((IkReal(-1.00000000000000))*(x673)*(x676)))+(((IkReal(-1.00000000000000))*(x668)*(x672)*(x674))));
2887 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
2888 {
2889 continue;
2890 }
2891 }
2892 
2893 {
2894 IkReal dummyeval[1];
2895 IkReal gconst21;
2896 gconst21=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
2897 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
2898 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2899 {
2900 {
2901 IkReal dummyeval[1];
2902 IkReal gconst22;
2903 gconst22=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
2904 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
2905 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
2906 {
2907 continue;
2908 
2909 } else
2910 {
2911 {
2912 IkReal j4array[1], cj4array[1], sj4array[1];
2913 bool j4valid[1]={false};
2914 _nj4 = 1;
2915 IkReal x679=((cj8)*(sj5));
2916 IkReal x680=((cj3)*(r01));
2917 IkReal x681=((IkReal(1.00000000000000))*(cj5));
2918 IkReal x682=((r11)*(sj3));
2919 IkReal x683=((sj5)*(sj8));
2920 IkReal x684=((r10)*(sj3));
2921 IkReal x685=((cj3)*(r00)*(sj8));
2922 if( IKabs(((gconst22)*(((((cj3)*(r00)*(x683)))+(((cj5)*(r20)*(sj8)))+(((x683)*(x684)))+(((x679)*(x682)))+(((x679)*(x680)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst22)*(((((r21)*(x679)))+(((IkReal(-1.00000000000000))*(x681)*(x685)))+(((IkReal(-1.00000000000000))*(cj8)*(x680)*(x681)))+(((IkReal(-1.00000000000000))*(cj8)*(x681)*(x682)))+(((r20)*(x683)))+(((IkReal(-1.00000000000000))*(sj8)*(x681)*(x684))))))) < IKFAST_ATAN2_MAGTHRESH )
2923  continue;
2924 j4array[0]=IKatan2(((gconst22)*(((((cj3)*(r00)*(x683)))+(((cj5)*(r20)*(sj8)))+(((x683)*(x684)))+(((x679)*(x682)))+(((x679)*(x680)))+(((cj5)*(cj8)*(r21)))))), ((gconst22)*(((((r21)*(x679)))+(((IkReal(-1.00000000000000))*(x681)*(x685)))+(((IkReal(-1.00000000000000))*(cj8)*(x680)*(x681)))+(((IkReal(-1.00000000000000))*(cj8)*(x681)*(x682)))+(((r20)*(x683)))+(((IkReal(-1.00000000000000))*(sj8)*(x681)*(x684)))))));
2925 sj4array[0]=IKsin(j4array[0]);
2926 cj4array[0]=IKcos(j4array[0]);
2927 if( j4array[0] > IKPI )
2928 {
2929  j4array[0]-=IK2PI;
2930 }
2931 else if( j4array[0] < -IKPI )
2932 { j4array[0]+=IK2PI;
2933 }
2934 j4valid[0] = true;
2935 for(int ij4 = 0; ij4 < 1; ++ij4)
2936 {
2937 if( !j4valid[ij4] )
2938 {
2939  continue;
2940 }
2941 _ij4[0] = ij4; _ij4[1] = -1;
2942 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
2943 {
2944 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
2945 {
2946  j4valid[iij4]=false; _ij4[1] = iij4; break;
2947 }
2948 }
2949 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
2950 {
2951 IkReal evalcond[4];
2952 IkReal x686=IKsin(j4);
2953 IkReal x687=IKcos(j4);
2954 IkReal x688=((IkReal(1.00000000000000))*(cj8));
2955 IkReal x689=((cj3)*(r01));
2956 IkReal x690=((cj3)*(r00));
2957 IkReal x691=((cj7)*(cj8));
2958 IkReal x692=((IkReal(1.00000000000000))*(cj5));
2959 IkReal x693=((IkReal(1.00000000000000))*(sj8));
2960 IkReal x694=((r11)*(sj3));
2961 IkReal x695=((r10)*(sj3));
2962 IkReal x696=((sj5)*(x686));
2963 IkReal x697=((sj5)*(x687));
2964 IkReal x698=((x687)*(x692));
2965 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x686)*(x692)))+(((r20)*(sj8)))+(((IkReal(-1.00000000000000))*(x697))));
2966 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x688)))+(x696)+(((IkReal(-1.00000000000000))*(x698)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
2967 evalcond[2]=((((IkReal(-1.00000000000000))*(x688)*(x689)))+(((IkReal(-1.00000000000000))*(x693)*(x695)))+(((IkReal(-1.00000000000000))*(x688)*(x694)))+(x696)+(((IkReal(-1.00000000000000))*(x698)))+(((IkReal(-1.00000000000000))*(x690)*(x693))));
2968 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((cj5)*(x686)))+(((x690)*(x691)))+(((x691)*(x695)))+(((cj3)*(r02)*(sj7)))+(x697)+(((IkReal(-1.00000000000000))*(cj7)*(x689)*(x693)))+(((IkReal(-1.00000000000000))*(cj7)*(x693)*(x694))));
2969 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
2970 {
2971 continue;
2972 }
2973 }
2974 
2975 {
2976 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2977 vinfos[0].jointtype = 1;
2978 vinfos[0].foffset = j3;
2979 vinfos[0].indices[0] = _ij3[0];
2980 vinfos[0].indices[1] = _ij3[1];
2981 vinfos[0].maxsolutions = _nj3;
2982 vinfos[1].jointtype = 1;
2983 vinfos[1].foffset = j4;
2984 vinfos[1].indices[0] = _ij4[0];
2985 vinfos[1].indices[1] = _ij4[1];
2986 vinfos[1].maxsolutions = _nj4;
2987 vinfos[2].jointtype = 1;
2988 vinfos[2].foffset = j5;
2989 vinfos[2].indices[0] = _ij5[0];
2990 vinfos[2].indices[1] = _ij5[1];
2991 vinfos[2].maxsolutions = _nj5;
2992 vinfos[3].jointtype = 1;
2993 vinfos[3].foffset = j6;
2994 vinfos[3].indices[0] = _ij6[0];
2995 vinfos[3].indices[1] = _ij6[1];
2996 vinfos[3].maxsolutions = _nj6;
2997 vinfos[4].jointtype = 1;
2998 vinfos[4].foffset = j7;
2999 vinfos[4].indices[0] = _ij7[0];
3000 vinfos[4].indices[1] = _ij7[1];
3001 vinfos[4].maxsolutions = _nj7;
3002 vinfos[5].jointtype = 1;
3003 vinfos[5].foffset = j8;
3004 vinfos[5].indices[0] = _ij8[0];
3005 vinfos[5].indices[1] = _ij8[1];
3006 vinfos[5].maxsolutions = _nj8;
3007 std::vector<int> vfree(0);
3008 solutions.AddSolution(vinfos,vfree);
3009 }
3010 }
3011 }
3012 
3013 }
3014 
3015 }
3016 
3017 } else
3018 {
3019 {
3020 IkReal j4array[1], cj4array[1], sj4array[1];
3021 bool j4valid[1]={false};
3022 _nj4 = 1;
3023 IkReal x699=((sj5)*(sj8));
3024 IkReal x700=((IkReal(1.00000000000000))*(cj7));
3025 IkReal x701=((cj8)*(sj5));
3026 IkReal x702=((r22)*(sj7));
3027 IkReal x703=((cj5)*(cj8));
3028 IkReal x704=((cj5)*(sj8));
3029 if( IKabs(((gconst21)*(((((cj7)*(r20)*(x701)))+(((sj5)*(x702)))+(((r20)*(x704)))+(((IkReal(-1.00000000000000))*(r21)*(x699)*(x700)))+(((r21)*(x703))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(cj5)*(x702)))+(((r20)*(x699)))+(((IkReal(-1.00000000000000))*(r20)*(x700)*(x703)))+(((r21)*(x701)))+(((cj7)*(r21)*(x704))))))) < IKFAST_ATAN2_MAGTHRESH )
3030  continue;
3031 j4array[0]=IKatan2(((gconst21)*(((((cj7)*(r20)*(x701)))+(((sj5)*(x702)))+(((r20)*(x704)))+(((IkReal(-1.00000000000000))*(r21)*(x699)*(x700)))+(((r21)*(x703)))))), ((gconst21)*(((((IkReal(-1.00000000000000))*(cj5)*(x702)))+(((r20)*(x699)))+(((IkReal(-1.00000000000000))*(r20)*(x700)*(x703)))+(((r21)*(x701)))+(((cj7)*(r21)*(x704)))))));
3032 sj4array[0]=IKsin(j4array[0]);
3033 cj4array[0]=IKcos(j4array[0]);
3034 if( j4array[0] > IKPI )
3035 {
3036  j4array[0]-=IK2PI;
3037 }
3038 else if( j4array[0] < -IKPI )
3039 { j4array[0]+=IK2PI;
3040 }
3041 j4valid[0] = true;
3042 for(int ij4 = 0; ij4 < 1; ++ij4)
3043 {
3044 if( !j4valid[ij4] )
3045 {
3046  continue;
3047 }
3048 _ij4[0] = ij4; _ij4[1] = -1;
3049 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
3050 {
3051 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
3052 {
3053  j4valid[iij4]=false; _ij4[1] = iij4; break;
3054 }
3055 }
3056 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
3057 {
3058 IkReal evalcond[4];
3059 IkReal x705=IKsin(j4);
3060 IkReal x706=IKcos(j4);
3061 IkReal x707=((IkReal(1.00000000000000))*(cj8));
3062 IkReal x708=((cj3)*(r01));
3063 IkReal x709=((cj3)*(r00));
3064 IkReal x710=((cj7)*(cj8));
3065 IkReal x711=((IkReal(1.00000000000000))*(cj5));
3066 IkReal x712=((IkReal(1.00000000000000))*(sj8));
3067 IkReal x713=((r11)*(sj3));
3068 IkReal x714=((r10)*(sj3));
3069 IkReal x715=((sj5)*(x705));
3070 IkReal x716=((sj5)*(x706));
3071 IkReal x717=((x706)*(x711));
3072 evalcond[0]=((((IkReal(-1.00000000000000))*(x716)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x705)*(x711)))+(((r20)*(sj8))));
3073 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x707)))+(((IkReal(-1.00000000000000))*(x717)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x715)+(((cj7)*(r21)*(sj8))));
3074 evalcond[2]=((((IkReal(-1.00000000000000))*(x707)*(x708)))+(((IkReal(-1.00000000000000))*(x707)*(x713)))+(((IkReal(-1.00000000000000))*(x709)*(x712)))+(((IkReal(-1.00000000000000))*(x717)))+(((IkReal(-1.00000000000000))*(x712)*(x714)))+(x715));
3075 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x708)*(x712)))+(((cj5)*(x705)))+(((x709)*(x710)))+(((x710)*(x714)))+(((IkReal(-1.00000000000000))*(cj7)*(x712)*(x713)))+(((cj3)*(r02)*(sj7)))+(x716));
3076 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
3077 {
3078 continue;
3079 }
3080 }
3081 
3082 {
3083 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3084 vinfos[0].jointtype = 1;
3085 vinfos[0].foffset = j3;
3086 vinfos[0].indices[0] = _ij3[0];
3087 vinfos[0].indices[1] = _ij3[1];
3088 vinfos[0].maxsolutions = _nj3;
3089 vinfos[1].jointtype = 1;
3090 vinfos[1].foffset = j4;
3091 vinfos[1].indices[0] = _ij4[0];
3092 vinfos[1].indices[1] = _ij4[1];
3093 vinfos[1].maxsolutions = _nj4;
3094 vinfos[2].jointtype = 1;
3095 vinfos[2].foffset = j5;
3096 vinfos[2].indices[0] = _ij5[0];
3097 vinfos[2].indices[1] = _ij5[1];
3098 vinfos[2].maxsolutions = _nj5;
3099 vinfos[3].jointtype = 1;
3100 vinfos[3].foffset = j6;
3101 vinfos[3].indices[0] = _ij6[0];
3102 vinfos[3].indices[1] = _ij6[1];
3103 vinfos[3].maxsolutions = _nj6;
3104 vinfos[4].jointtype = 1;
3105 vinfos[4].foffset = j7;
3106 vinfos[4].indices[0] = _ij7[0];
3107 vinfos[4].indices[1] = _ij7[1];
3108 vinfos[4].maxsolutions = _nj7;
3109 vinfos[5].jointtype = 1;
3110 vinfos[5].foffset = j8;
3111 vinfos[5].indices[0] = _ij8[0];
3112 vinfos[5].indices[1] = _ij8[1];
3113 vinfos[5].maxsolutions = _nj8;
3114 std::vector<int> vfree(0);
3115 solutions.AddSolution(vinfos,vfree);
3116 }
3117 }
3118 }
3119 
3120 }
3121 
3122 }
3123 }
3124 }
3125 
3126 }
3127 
3128 }
3129 
3130 } else
3131 {
3132 {
3133 IkReal j3array[1], cj3array[1], sj3array[1];
3134 bool j3valid[1]={false};
3135 _nj3 = 1;
3136 IkReal x718=((IkReal(1.00000000000000))*(cj8));
3137 IkReal x719=((IkReal(1.00000000000000))*(sj8));
3138 if( IKabs(((gconst18)*(((((IkReal(-1.00000000000000))*(r11)*(x718)))+(((IkReal(-1.00000000000000))*(r10)*(x719))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst18)*(((((IkReal(-1.00000000000000))*(r01)*(x718)))+(((IkReal(-1.00000000000000))*(r00)*(x719))))))) < IKFAST_ATAN2_MAGTHRESH )
3139  continue;
3140 j3array[0]=IKatan2(((gconst18)*(((((IkReal(-1.00000000000000))*(r11)*(x718)))+(((IkReal(-1.00000000000000))*(r10)*(x719)))))), ((gconst18)*(((((IkReal(-1.00000000000000))*(r01)*(x718)))+(((IkReal(-1.00000000000000))*(r00)*(x719)))))));
3141 sj3array[0]=IKsin(j3array[0]);
3142 cj3array[0]=IKcos(j3array[0]);
3143 if( j3array[0] > IKPI )
3144 {
3145  j3array[0]-=IK2PI;
3146 }
3147 else if( j3array[0] < -IKPI )
3148 { j3array[0]+=IK2PI;
3149 }
3150 j3valid[0] = true;
3151 for(int ij3 = 0; ij3 < 1; ++ij3)
3152 {
3153 if( !j3valid[ij3] )
3154 {
3155  continue;
3156 }
3157 _ij3[0] = ij3; _ij3[1] = -1;
3158 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
3159 {
3160 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
3161 {
3162  j3valid[iij3]=false; _ij3[1] = iij3; break;
3163 }
3164 }
3165 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
3166 {
3167 IkReal evalcond[4];
3168 IkReal x720=IKsin(j3);
3169 IkReal x721=IKcos(j3);
3170 IkReal x722=((r01)*(sj8));
3171 IkReal x723=((cj8)*(sj7));
3172 IkReal x724=((IkReal(1.00000000000000))*(sj7));
3173 IkReal x725=((IkReal(1.00000000000000))*(r12));
3174 IkReal x726=((r11)*(sj8));
3175 IkReal x727=((IkReal(1.00000000000000))*(r00));
3176 IkReal x728=((cj7)*(x720));
3177 IkReal x729=((r10)*(x721));
3178 IkReal x730=((IkReal(1.00000000000000))*(cj7)*(x721));
3179 evalcond[0]=((((r00)*(sj8)*(x720)))+(((IkReal(-1.00000000000000))*(sj8)*(x729)))+(((cj8)*(r01)*(x720)))+(((IkReal(-1.00000000000000))*(cj8)*(r11)*(x721))));
3180 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(x727)*(x728)))+(((x722)*(x728)))+(((IkReal(-1.00000000000000))*(r02)*(x720)*(x724)))+(((cj7)*(cj8)*(x729)))+(((r12)*(sj7)*(x721)))+(((IkReal(-1.00000000000000))*(x726)*(x730))));
3181 evalcond[2]=((IkReal(1.00000000000000))+(((x723)*(x729)))+(((IkReal(-1.00000000000000))*(cj7)*(x721)*(x725)))+(((IkReal(-1.00000000000000))*(x720)*(x723)*(x727)))+(((IkReal(-1.00000000000000))*(x721)*(x724)*(x726)))+(((sj7)*(x720)*(x722)))+(((r02)*(x728))));
3182 evalcond[3]=((((r10)*(x720)*(x723)))+(((IkReal(-1.00000000000000))*(r02)*(x730)))+(((IkReal(-1.00000000000000))*(x721)*(x722)*(x724)))+(((IkReal(-1.00000000000000))*(x725)*(x728)))+(((r00)*(x721)*(x723)))+(((IkReal(-1.00000000000000))*(x720)*(x724)*(x726))));
3183 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
3184 {
3185 continue;
3186 }
3187 }
3188 
3189 {
3190 IkReal dummyeval[1];
3191 IkReal gconst21;
3192 gconst21=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
3193 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
3194 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3195 {
3196 {
3197 IkReal dummyeval[1];
3198 IkReal gconst22;
3199 gconst22=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
3200 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
3201 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3202 {
3203 continue;
3204 
3205 } else
3206 {
3207 {
3208 IkReal j4array[1], cj4array[1], sj4array[1];
3209 bool j4valid[1]={false};
3210 _nj4 = 1;
3211 IkReal x731=((cj8)*(sj5));
3212 IkReal x732=((cj3)*(r01));
3213 IkReal x733=((IkReal(1.00000000000000))*(cj5));
3214 IkReal x734=((r11)*(sj3));
3215 IkReal x735=((sj5)*(sj8));
3216 IkReal x736=((r10)*(sj3));
3217 IkReal x737=((cj3)*(r00)*(sj8));
3218 if( IKabs(((gconst22)*(((((x731)*(x734)))+(((x731)*(x732)))+(((x735)*(x736)))+(((cj5)*(r20)*(sj8)))+(((cj3)*(r00)*(x735)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst22)*(((((IkReal(-1.00000000000000))*(sj8)*(x733)*(x736)))+(((IkReal(-1.00000000000000))*(x733)*(x737)))+(((r20)*(x735)))+(((IkReal(-1.00000000000000))*(cj8)*(x732)*(x733)))+(((r21)*(x731)))+(((IkReal(-1.00000000000000))*(cj8)*(x733)*(x734))))))) < IKFAST_ATAN2_MAGTHRESH )
3219  continue;
3220 j4array[0]=IKatan2(((gconst22)*(((((x731)*(x734)))+(((x731)*(x732)))+(((x735)*(x736)))+(((cj5)*(r20)*(sj8)))+(((cj3)*(r00)*(x735)))+(((cj5)*(cj8)*(r21)))))), ((gconst22)*(((((IkReal(-1.00000000000000))*(sj8)*(x733)*(x736)))+(((IkReal(-1.00000000000000))*(x733)*(x737)))+(((r20)*(x735)))+(((IkReal(-1.00000000000000))*(cj8)*(x732)*(x733)))+(((r21)*(x731)))+(((IkReal(-1.00000000000000))*(cj8)*(x733)*(x734)))))));
3221 sj4array[0]=IKsin(j4array[0]);
3222 cj4array[0]=IKcos(j4array[0]);
3223 if( j4array[0] > IKPI )
3224 {
3225  j4array[0]-=IK2PI;
3226 }
3227 else if( j4array[0] < -IKPI )
3228 { j4array[0]+=IK2PI;
3229 }
3230 j4valid[0] = true;
3231 for(int ij4 = 0; ij4 < 1; ++ij4)
3232 {
3233 if( !j4valid[ij4] )
3234 {
3235  continue;
3236 }
3237 _ij4[0] = ij4; _ij4[1] = -1;
3238 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
3239 {
3240 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
3241 {
3242  j4valid[iij4]=false; _ij4[1] = iij4; break;
3243 }
3244 }
3245 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
3246 {
3247 IkReal evalcond[4];
3248 IkReal x738=IKsin(j4);
3249 IkReal x739=IKcos(j4);
3250 IkReal x740=((IkReal(1.00000000000000))*(cj8));
3251 IkReal x741=((cj3)*(r01));
3252 IkReal x742=((cj3)*(r00));
3253 IkReal x743=((cj7)*(cj8));
3254 IkReal x744=((IkReal(1.00000000000000))*(cj5));
3255 IkReal x745=((IkReal(1.00000000000000))*(sj8));
3256 IkReal x746=((r11)*(sj3));
3257 IkReal x747=((r10)*(sj3));
3258 IkReal x748=((sj5)*(x738));
3259 IkReal x749=((sj5)*(x739));
3260 IkReal x750=((x739)*(x744));
3261 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x738)*(x744)))+(((IkReal(-1.00000000000000))*(x749)))+(((r20)*(sj8))));
3262 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x748)+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(x750)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x740))));
3263 evalcond[2]=((((IkReal(-1.00000000000000))*(x745)*(x747)))+(((IkReal(-1.00000000000000))*(x742)*(x745)))+(((IkReal(-1.00000000000000))*(x740)*(x741)))+(((IkReal(-1.00000000000000))*(x740)*(x746)))+(x748)+(((IkReal(-1.00000000000000))*(x750))));
3264 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((cj5)*(x738)))+(((x742)*(x743)))+(((IkReal(-1.00000000000000))*(cj7)*(x741)*(x745)))+(((IkReal(-1.00000000000000))*(cj7)*(x745)*(x746)))+(((cj3)*(r02)*(sj7)))+(((x743)*(x747)))+(x749));
3265 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
3266 {
3267 continue;
3268 }
3269 }
3270 
3271 {
3272 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3273 vinfos[0].jointtype = 1;
3274 vinfos[0].foffset = j3;
3275 vinfos[0].indices[0] = _ij3[0];
3276 vinfos[0].indices[1] = _ij3[1];
3277 vinfos[0].maxsolutions = _nj3;
3278 vinfos[1].jointtype = 1;
3279 vinfos[1].foffset = j4;
3280 vinfos[1].indices[0] = _ij4[0];
3281 vinfos[1].indices[1] = _ij4[1];
3282 vinfos[1].maxsolutions = _nj4;
3283 vinfos[2].jointtype = 1;
3284 vinfos[2].foffset = j5;
3285 vinfos[2].indices[0] = _ij5[0];
3286 vinfos[2].indices[1] = _ij5[1];
3287 vinfos[2].maxsolutions = _nj5;
3288 vinfos[3].jointtype = 1;
3289 vinfos[3].foffset = j6;
3290 vinfos[3].indices[0] = _ij6[0];
3291 vinfos[3].indices[1] = _ij6[1];
3292 vinfos[3].maxsolutions = _nj6;
3293 vinfos[4].jointtype = 1;
3294 vinfos[4].foffset = j7;
3295 vinfos[4].indices[0] = _ij7[0];
3296 vinfos[4].indices[1] = _ij7[1];
3297 vinfos[4].maxsolutions = _nj7;
3298 vinfos[5].jointtype = 1;
3299 vinfos[5].foffset = j8;
3300 vinfos[5].indices[0] = _ij8[0];
3301 vinfos[5].indices[1] = _ij8[1];
3302 vinfos[5].maxsolutions = _nj8;
3303 std::vector<int> vfree(0);
3304 solutions.AddSolution(vinfos,vfree);
3305 }
3306 }
3307 }
3308 
3309 }
3310 
3311 }
3312 
3313 } else
3314 {
3315 {
3316 IkReal j4array[1], cj4array[1], sj4array[1];
3317 bool j4valid[1]={false};
3318 _nj4 = 1;
3319 IkReal x751=((sj5)*(sj8));
3320 IkReal x752=((IkReal(1.00000000000000))*(cj7));
3321 IkReal x753=((cj8)*(sj5));
3322 IkReal x754=((r22)*(sj7));
3323 IkReal x755=((cj5)*(cj8));
3324 IkReal x756=((cj5)*(sj8));
3325 if( IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(r21)*(x751)*(x752)))+(((cj7)*(r20)*(x753)))+(((r21)*(x755)))+(((sj5)*(x754)))+(((r20)*(x756))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst21)*(((((r21)*(x753)))+(((cj7)*(r21)*(x756)))+(((IkReal(-1.00000000000000))*(cj5)*(x754)))+(((r20)*(x751)))+(((IkReal(-1.00000000000000))*(r20)*(x752)*(x755))))))) < IKFAST_ATAN2_MAGTHRESH )
3326  continue;
3327 j4array[0]=IKatan2(((gconst21)*(((((IkReal(-1.00000000000000))*(r21)*(x751)*(x752)))+(((cj7)*(r20)*(x753)))+(((r21)*(x755)))+(((sj5)*(x754)))+(((r20)*(x756)))))), ((gconst21)*(((((r21)*(x753)))+(((cj7)*(r21)*(x756)))+(((IkReal(-1.00000000000000))*(cj5)*(x754)))+(((r20)*(x751)))+(((IkReal(-1.00000000000000))*(r20)*(x752)*(x755)))))));
3328 sj4array[0]=IKsin(j4array[0]);
3329 cj4array[0]=IKcos(j4array[0]);
3330 if( j4array[0] > IKPI )
3331 {
3332  j4array[0]-=IK2PI;
3333 }
3334 else if( j4array[0] < -IKPI )
3335 { j4array[0]+=IK2PI;
3336 }
3337 j4valid[0] = true;
3338 for(int ij4 = 0; ij4 < 1; ++ij4)
3339 {
3340 if( !j4valid[ij4] )
3341 {
3342  continue;
3343 }
3344 _ij4[0] = ij4; _ij4[1] = -1;
3345 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
3346 {
3347 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
3348 {
3349  j4valid[iij4]=false; _ij4[1] = iij4; break;
3350 }
3351 }
3352 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
3353 {
3354 IkReal evalcond[4];
3355 IkReal x757=IKsin(j4);
3356 IkReal x758=IKcos(j4);
3357 IkReal x759=((IkReal(1.00000000000000))*(cj8));
3358 IkReal x760=((cj3)*(r01));
3359 IkReal x761=((cj3)*(r00));
3360 IkReal x762=((cj7)*(cj8));
3361 IkReal x763=((IkReal(1.00000000000000))*(cj5));
3362 IkReal x764=((IkReal(1.00000000000000))*(sj8));
3363 IkReal x765=((r11)*(sj3));
3364 IkReal x766=((r10)*(sj3));
3365 IkReal x767=((sj5)*(x757));
3366 IkReal x768=((sj5)*(x758));
3367 IkReal x769=((x758)*(x763));
3368 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x757)*(x763)))+(((IkReal(-1.00000000000000))*(x768)))+(((r20)*(sj8))));
3369 evalcond[1]=((((IkReal(-1.00000000000000))*(x769)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x767)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x759)))+(((cj7)*(r21)*(sj8))));
3370 evalcond[2]=((((IkReal(-1.00000000000000))*(x769)))+(((IkReal(-1.00000000000000))*(x764)*(x766)))+(x767)+(((IkReal(-1.00000000000000))*(x761)*(x764)))+(((IkReal(-1.00000000000000))*(x759)*(x765)))+(((IkReal(-1.00000000000000))*(x759)*(x760))));
3371 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((cj5)*(x757)))+(((x761)*(x762)))+(((x762)*(x766)))+(((IkReal(-1.00000000000000))*(cj7)*(x764)*(x765)))+(((cj3)*(r02)*(sj7)))+(x768)+(((IkReal(-1.00000000000000))*(cj7)*(x760)*(x764))));
3372 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
3373 {
3374 continue;
3375 }
3376 }
3377 
3378 {
3379 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3380 vinfos[0].jointtype = 1;
3381 vinfos[0].foffset = j3;
3382 vinfos[0].indices[0] = _ij3[0];
3383 vinfos[0].indices[1] = _ij3[1];
3384 vinfos[0].maxsolutions = _nj3;
3385 vinfos[1].jointtype = 1;
3386 vinfos[1].foffset = j4;
3387 vinfos[1].indices[0] = _ij4[0];
3388 vinfos[1].indices[1] = _ij4[1];
3389 vinfos[1].maxsolutions = _nj4;
3390 vinfos[2].jointtype = 1;
3391 vinfos[2].foffset = j5;
3392 vinfos[2].indices[0] = _ij5[0];
3393 vinfos[2].indices[1] = _ij5[1];
3394 vinfos[2].maxsolutions = _nj5;
3395 vinfos[3].jointtype = 1;
3396 vinfos[3].foffset = j6;
3397 vinfos[3].indices[0] = _ij6[0];
3398 vinfos[3].indices[1] = _ij6[1];
3399 vinfos[3].maxsolutions = _nj6;
3400 vinfos[4].jointtype = 1;
3401 vinfos[4].foffset = j7;
3402 vinfos[4].indices[0] = _ij7[0];
3403 vinfos[4].indices[1] = _ij7[1];
3404 vinfos[4].maxsolutions = _nj7;
3405 vinfos[5].jointtype = 1;
3406 vinfos[5].foffset = j8;
3407 vinfos[5].indices[0] = _ij8[0];
3408 vinfos[5].indices[1] = _ij8[1];
3409 vinfos[5].maxsolutions = _nj8;
3410 std::vector<int> vfree(0);
3411 solutions.AddSolution(vinfos,vfree);
3412 }
3413 }
3414 }
3415 
3416 }
3417 
3418 }
3419 }
3420 }
3421 
3422 }
3423 
3424 }
3425 
3426 } else
3427 {
3428 {
3429 IkReal j4array[1], cj4array[1], sj4array[1];
3430 bool j4valid[1]={false};
3431 _nj4 = 1;
3432 IkReal x770=((sj5)*(sj8));
3433 IkReal x771=((IkReal(1.00000000000000))*(cj7));
3434 IkReal x772=((cj8)*(sj5));
3435 IkReal x773=((r22)*(sj7));
3436 IkReal x774=((cj5)*(cj8));
3437 IkReal x775=((cj5)*(sj8));
3438 if( IKabs(((gconst20)*(((((cj7)*(r20)*(x772)))+(((IkReal(-1.00000000000000))*(r21)*(x770)*(x771)))+(((r21)*(x774)))+(((r20)*(x775)))+(((sj5)*(x773))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst20)*(((((cj7)*(r21)*(x775)))+(((r21)*(x772)))+(((IkReal(-1.00000000000000))*(cj5)*(x773)))+(((r20)*(x770)))+(((IkReal(-1.00000000000000))*(r20)*(x771)*(x774))))))) < IKFAST_ATAN2_MAGTHRESH )
3439  continue;
3440 j4array[0]=IKatan2(((gconst20)*(((((cj7)*(r20)*(x772)))+(((IkReal(-1.00000000000000))*(r21)*(x770)*(x771)))+(((r21)*(x774)))+(((r20)*(x775)))+(((sj5)*(x773)))))), ((gconst20)*(((((cj7)*(r21)*(x775)))+(((r21)*(x772)))+(((IkReal(-1.00000000000000))*(cj5)*(x773)))+(((r20)*(x770)))+(((IkReal(-1.00000000000000))*(r20)*(x771)*(x774)))))));
3441 sj4array[0]=IKsin(j4array[0]);
3442 cj4array[0]=IKcos(j4array[0]);
3443 if( j4array[0] > IKPI )
3444 {
3445  j4array[0]-=IK2PI;
3446 }
3447 else if( j4array[0] < -IKPI )
3448 { j4array[0]+=IK2PI;
3449 }
3450 j4valid[0] = true;
3451 for(int ij4 = 0; ij4 < 1; ++ij4)
3452 {
3453 if( !j4valid[ij4] )
3454 {
3455  continue;
3456 }
3457 _ij4[0] = ij4; _ij4[1] = -1;
3458 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
3459 {
3460 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
3461 {
3462  j4valid[iij4]=false; _ij4[1] = iij4; break;
3463 }
3464 }
3465 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
3466 {
3467 IkReal evalcond[2];
3468 IkReal x776=IKsin(j4);
3469 IkReal x777=IKcos(j4);
3470 IkReal x778=((IkReal(1.00000000000000))*(cj5));
3471 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x776)*(x778)))+(((IkReal(-1.00000000000000))*(sj5)*(x777)))+(((r20)*(sj8))));
3472 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(cj8)*(r20)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((sj5)*(x776)))+(((IkReal(-1.00000000000000))*(x777)*(x778)))+(((cj7)*(r21)*(sj8))));
3473 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
3474 {
3475 continue;
3476 }
3477 }
3478 
3479 {
3480 IkReal dummyeval[1];
3481 IkReal gconst24;
3482 IkReal x779=(cj8)*(cj8);
3483 IkReal x780=(sj8)*(sj8);
3484 IkReal x781=((cj7)*(r02));
3485 IkReal x782=((IkReal(1.00000000000000))*(r00));
3486 IkReal x783=((cj7)*(r12));
3487 IkReal x784=((r01)*(r10));
3488 IkReal x785=((sj7)*(x780));
3489 IkReal x786=((sj7)*(x779));
3490 gconst24=IKsign(((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x783)))+(((x784)*(x786)))+(((x784)*(x785)))+(((IkReal(-1.00000000000000))*(r11)*(x782)*(x786)))+(((IkReal(-1.00000000000000))*(r11)*(x782)*(x785)))+(((r10)*(sj8)*(x781)))+(((IkReal(-1.00000000000000))*(sj8)*(x782)*(x783)))+(((cj8)*(r11)*(x781)))));
3491 IkReal x787=(cj8)*(cj8);
3492 IkReal x788=(sj8)*(sj8);
3493 IkReal x789=((cj7)*(r02));
3494 IkReal x790=((IkReal(1.00000000000000))*(r00));
3495 IkReal x791=((cj7)*(r12));
3496 IkReal x792=((r01)*(r10));
3497 IkReal x793=((sj7)*(x788));
3498 IkReal x794=((sj7)*(x787));
3499 dummyeval[0]=((((IkReal(-1.00000000000000))*(r11)*(x790)*(x794)))+(((IkReal(-1.00000000000000))*(r11)*(x790)*(x793)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x791)))+(((x792)*(x794)))+(((x792)*(x793)))+(((r10)*(sj8)*(x789)))+(((IkReal(-1.00000000000000))*(sj8)*(x790)*(x791)))+(((cj8)*(r11)*(x789))));
3500 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3501 {
3502 {
3503 IkReal dummyeval[1];
3504 IkReal gconst23;
3505 IkReal x795=(cj8)*(cj8);
3506 IkReal x796=(sj8)*(sj8);
3507 IkReal x797=((IkReal(2.00000000000000))*(cj8)*(sj8));
3508 IkReal x798=((IkReal(1.00000000000000))*(x795));
3509 IkReal x799=((IkReal(1.00000000000000))*(x796));
3510 gconst23=IKsign(((((IkReal(-1.00000000000000))*(x799)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x798)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x799)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x797)))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x797)))+(((IkReal(-1.00000000000000))*(x798)*((r01)*(r01))))));
3511 IkReal x800=(cj8)*(cj8);
3512 IkReal x801=(sj8)*(sj8);
3513 IkReal x802=((IkReal(2.00000000000000))*(cj8)*(sj8));
3514 IkReal x803=((IkReal(1.00000000000000))*(x800));
3515 IkReal x804=((IkReal(1.00000000000000))*(x801));
3516 dummyeval[0]=((((IkReal(-1.00000000000000))*(x803)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x802)))+(((IkReal(-1.00000000000000))*(x804)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x803)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x804)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x802))));
3517 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3518 {
3519 continue;
3520 
3521 } else
3522 {
3523 {
3524 IkReal j3array[1], cj3array[1], sj3array[1];
3525 bool j3valid[1]={false};
3526 _nj3 = 1;
3527 IkReal x805=((cj8)*(r01));
3528 IkReal x806=((cj4)*(cj5));
3529 IkReal x807=((r10)*(sj8));
3530 IkReal x808=((cj8)*(r11));
3531 IkReal x809=((r00)*(sj8));
3532 IkReal x810=((IkReal(1.00000000000000))*(sj4)*(sj5));
3533 if( IKabs(((gconst23)*(((((x806)*(x808)))+(((x806)*(x807)))+(((IkReal(-1.00000000000000))*(x808)*(x810)))+(((IkReal(-1.00000000000000))*(x807)*(x810))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst23)*(((((x806)*(x809)))+(((IkReal(-1.00000000000000))*(x809)*(x810)))+(((x805)*(x806)))+(((IkReal(-1.00000000000000))*(x805)*(x810))))))) < IKFAST_ATAN2_MAGTHRESH )
3534  continue;
3535 j3array[0]=IKatan2(((gconst23)*(((((x806)*(x808)))+(((x806)*(x807)))+(((IkReal(-1.00000000000000))*(x808)*(x810)))+(((IkReal(-1.00000000000000))*(x807)*(x810)))))), ((gconst23)*(((((x806)*(x809)))+(((IkReal(-1.00000000000000))*(x809)*(x810)))+(((x805)*(x806)))+(((IkReal(-1.00000000000000))*(x805)*(x810)))))));
3536 sj3array[0]=IKsin(j3array[0]);
3537 cj3array[0]=IKcos(j3array[0]);
3538 if( j3array[0] > IKPI )
3539 {
3540  j3array[0]-=IK2PI;
3541 }
3542 else if( j3array[0] < -IKPI )
3543 { j3array[0]+=IK2PI;
3544 }
3545 j3valid[0] = true;
3546 for(int ij3 = 0; ij3 < 1; ++ij3)
3547 {
3548 if( !j3valid[ij3] )
3549 {
3550  continue;
3551 }
3552 _ij3[0] = ij3; _ij3[1] = -1;
3553 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
3554 {
3555 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
3556 {
3557  j3valid[iij3]=false; _ij3[1] = iij3; break;
3558 }
3559 }
3560 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
3561 {
3562 IkReal evalcond[6];
3563 IkReal x811=IKsin(j3);
3564 IkReal x812=IKcos(j3);
3565 IkReal x813=((cj7)*(sj8));
3566 IkReal x814=((r00)*(sj8));
3567 IkReal x815=((cj8)*(r11));
3568 IkReal x816=((cj7)*(r02));
3569 IkReal x817=((cj7)*(r12));
3570 IkReal x818=((cj8)*(r10));
3571 IkReal x819=((sj7)*(sj8));
3572 IkReal x820=((cj8)*(r00));
3573 IkReal x821=((r10)*(sj8));
3574 IkReal x822=((r01)*(x811));
3575 IkReal x823=((IkReal(1.00000000000000))*(x812));
3576 IkReal x824=((IkReal(1.00000000000000))*(x811));
3577 IkReal x825=((sj7)*(x811));
3578 IkReal x826=((sj7)*(x812));
3579 IkReal x827=((cj7)*(x812));
3580 IkReal x828=((cj8)*(x826));
3581 evalcond[0]=((((IkReal(-1.00000000000000))*(x815)*(x823)))+(((x811)*(x814)))+(((IkReal(-1.00000000000000))*(x821)*(x823)))+(((cj8)*(x822))));
3582 evalcond[1]=((((IkReal(-1.00000000000000))*(x814)*(x823)))+(((IkReal(-1.00000000000000))*(x815)*(x824)))+(((sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(x821)*(x824)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x823))));
3583 evalcond[2]=((((r12)*(x826)))+(((IkReal(-1.00000000000000))*(cj7)*(x820)*(x824)))+(((IkReal(-1.00000000000000))*(r11)*(x813)*(x823)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x824)))+(((x813)*(x822)))+(((x818)*(x827))));
3584 evalcond[3]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(sj7)*(x820)*(x824)))+(((IkReal(-1.00000000000000))*(r11)*(x819)*(x823)))+(((IkReal(-1.00000000000000))*(x817)*(x823)))+(((x819)*(x822)))+(((x811)*(x816)))+(((x818)*(x826))));
3585 evalcond[4]=((((cj7)*(x811)*(x818)))+(((r12)*(x825)))+(((x820)*(x827)))+(((IkReal(-1.00000000000000))*(r11)*(x813)*(x824)))+(((cj5)*(sj4)))+(((cj4)*(sj5)))+(((r02)*(x826)))+(((IkReal(-1.00000000000000))*(r01)*(x813)*(x823))));
3586 evalcond[5]=((((IkReal(-1.00000000000000))*(x816)*(x823)))+(((x820)*(x826)))+(((IkReal(-1.00000000000000))*(r11)*(x819)*(x824)))+(((IkReal(-1.00000000000000))*(x817)*(x824)))+(((x818)*(x825)))+(((IkReal(-1.00000000000000))*(r01)*(x819)*(x823))));
3587 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
3588 {
3589 continue;
3590 }
3591 }
3592 
3593 {
3594 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3595 vinfos[0].jointtype = 1;
3596 vinfos[0].foffset = j3;
3597 vinfos[0].indices[0] = _ij3[0];
3598 vinfos[0].indices[1] = _ij3[1];
3599 vinfos[0].maxsolutions = _nj3;
3600 vinfos[1].jointtype = 1;
3601 vinfos[1].foffset = j4;
3602 vinfos[1].indices[0] = _ij4[0];
3603 vinfos[1].indices[1] = _ij4[1];
3604 vinfos[1].maxsolutions = _nj4;
3605 vinfos[2].jointtype = 1;
3606 vinfos[2].foffset = j5;
3607 vinfos[2].indices[0] = _ij5[0];
3608 vinfos[2].indices[1] = _ij5[1];
3609 vinfos[2].maxsolutions = _nj5;
3610 vinfos[3].jointtype = 1;
3611 vinfos[3].foffset = j6;
3612 vinfos[3].indices[0] = _ij6[0];
3613 vinfos[3].indices[1] = _ij6[1];
3614 vinfos[3].maxsolutions = _nj6;
3615 vinfos[4].jointtype = 1;
3616 vinfos[4].foffset = j7;
3617 vinfos[4].indices[0] = _ij7[0];
3618 vinfos[4].indices[1] = _ij7[1];
3619 vinfos[4].maxsolutions = _nj7;
3620 vinfos[5].jointtype = 1;
3621 vinfos[5].foffset = j8;
3622 vinfos[5].indices[0] = _ij8[0];
3623 vinfos[5].indices[1] = _ij8[1];
3624 vinfos[5].maxsolutions = _nj8;
3625 std::vector<int> vfree(0);
3626 solutions.AddSolution(vinfos,vfree);
3627 }
3628 }
3629 }
3630 
3631 }
3632 
3633 }
3634 
3635 } else
3636 {
3637 {
3638 IkReal j3array[1], cj3array[1], sj3array[1];
3639 bool j3valid[1]={false};
3640 _nj3 = 1;
3641 IkReal x829=((IkReal(1.00000000000000))*(cj8));
3642 IkReal x830=((IkReal(1.00000000000000))*(sj8));
3643 if( IKabs(((gconst24)*(((((IkReal(-1.00000000000000))*(r11)*(x829)))+(((IkReal(-1.00000000000000))*(r10)*(x830))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst24)*(((((IkReal(-1.00000000000000))*(r01)*(x829)))+(((IkReal(-1.00000000000000))*(r00)*(x830))))))) < IKFAST_ATAN2_MAGTHRESH )
3644  continue;
3645 j3array[0]=IKatan2(((gconst24)*(((((IkReal(-1.00000000000000))*(r11)*(x829)))+(((IkReal(-1.00000000000000))*(r10)*(x830)))))), ((gconst24)*(((((IkReal(-1.00000000000000))*(r01)*(x829)))+(((IkReal(-1.00000000000000))*(r00)*(x830)))))));
3646 sj3array[0]=IKsin(j3array[0]);
3647 cj3array[0]=IKcos(j3array[0]);
3648 if( j3array[0] > IKPI )
3649 {
3650  j3array[0]-=IK2PI;
3651 }
3652 else if( j3array[0] < -IKPI )
3653 { j3array[0]+=IK2PI;
3654 }
3655 j3valid[0] = true;
3656 for(int ij3 = 0; ij3 < 1; ++ij3)
3657 {
3658 if( !j3valid[ij3] )
3659 {
3660  continue;
3661 }
3662 _ij3[0] = ij3; _ij3[1] = -1;
3663 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
3664 {
3665 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
3666 {
3667  j3valid[iij3]=false; _ij3[1] = iij3; break;
3668 }
3669 }
3670 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
3671 {
3672 IkReal evalcond[6];
3673 IkReal x831=IKsin(j3);
3674 IkReal x832=IKcos(j3);
3675 IkReal x833=((cj7)*(sj8));
3676 IkReal x834=((r00)*(sj8));
3677 IkReal x835=((cj8)*(r11));
3678 IkReal x836=((cj7)*(r02));
3679 IkReal x837=((cj7)*(r12));
3680 IkReal x838=((cj8)*(r10));
3681 IkReal x839=((sj7)*(sj8));
3682 IkReal x840=((cj8)*(r00));
3683 IkReal x841=((r10)*(sj8));
3684 IkReal x842=((r01)*(x831));
3685 IkReal x843=((IkReal(1.00000000000000))*(x832));
3686 IkReal x844=((IkReal(1.00000000000000))*(x831));
3687 IkReal x845=((sj7)*(x831));
3688 IkReal x846=((sj7)*(x832));
3689 IkReal x847=((cj7)*(x832));
3690 IkReal x848=((cj8)*(x846));
3691 evalcond[0]=((((x831)*(x834)))+(((IkReal(-1.00000000000000))*(x835)*(x843)))+(((IkReal(-1.00000000000000))*(x841)*(x843)))+(((cj8)*(x842))));
3692 evalcond[1]=((((IkReal(-1.00000000000000))*(x835)*(x844)))+(((IkReal(-1.00000000000000))*(x841)*(x844)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x843)))+(((sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(x834)*(x843)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5))));
3693 evalcond[2]=((((x838)*(x847)))+(((IkReal(-1.00000000000000))*(cj7)*(x840)*(x844)))+(((IkReal(-1.00000000000000))*(r11)*(x833)*(x843)))+(((x833)*(x842)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x844)))+(((r12)*(x846))));
3694 evalcond[3]=((IkReal(1.00000000000000))+(((x831)*(x836)))+(((x838)*(x846)))+(((x839)*(x842)))+(((IkReal(-1.00000000000000))*(x837)*(x843)))+(((IkReal(-1.00000000000000))*(sj7)*(x840)*(x844)))+(((IkReal(-1.00000000000000))*(r11)*(x839)*(x843))));
3695 evalcond[4]=((((x840)*(x847)))+(((IkReal(-1.00000000000000))*(r11)*(x833)*(x844)))+(((r02)*(x846)))+(((cj7)*(x831)*(x838)))+(((cj5)*(sj4)))+(((cj4)*(sj5)))+(((r12)*(x845)))+(((IkReal(-1.00000000000000))*(r01)*(x833)*(x843))));
3696 evalcond[5]=((((x838)*(x845)))+(((x840)*(x846)))+(((IkReal(-1.00000000000000))*(x836)*(x843)))+(((IkReal(-1.00000000000000))*(x837)*(x844)))+(((IkReal(-1.00000000000000))*(r01)*(x839)*(x843)))+(((IkReal(-1.00000000000000))*(r11)*(x839)*(x844))));
3697 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
3698 {
3699 continue;
3700 }
3701 }
3702 
3703 {
3704 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3705 vinfos[0].jointtype = 1;
3706 vinfos[0].foffset = j3;
3707 vinfos[0].indices[0] = _ij3[0];
3708 vinfos[0].indices[1] = _ij3[1];
3709 vinfos[0].maxsolutions = _nj3;
3710 vinfos[1].jointtype = 1;
3711 vinfos[1].foffset = j4;
3712 vinfos[1].indices[0] = _ij4[0];
3713 vinfos[1].indices[1] = _ij4[1];
3714 vinfos[1].maxsolutions = _nj4;
3715 vinfos[2].jointtype = 1;
3716 vinfos[2].foffset = j5;
3717 vinfos[2].indices[0] = _ij5[0];
3718 vinfos[2].indices[1] = _ij5[1];
3719 vinfos[2].maxsolutions = _nj5;
3720 vinfos[3].jointtype = 1;
3721 vinfos[3].foffset = j6;
3722 vinfos[3].indices[0] = _ij6[0];
3723 vinfos[3].indices[1] = _ij6[1];
3724 vinfos[3].maxsolutions = _nj6;
3725 vinfos[4].jointtype = 1;
3726 vinfos[4].foffset = j7;
3727 vinfos[4].indices[0] = _ij7[0];
3728 vinfos[4].indices[1] = _ij7[1];
3729 vinfos[4].maxsolutions = _nj7;
3730 vinfos[5].jointtype = 1;
3731 vinfos[5].foffset = j8;
3732 vinfos[5].indices[0] = _ij8[0];
3733 vinfos[5].indices[1] = _ij8[1];
3734 vinfos[5].maxsolutions = _nj8;
3735 std::vector<int> vfree(0);
3736 solutions.AddSolution(vinfos,vfree);
3737 }
3738 }
3739 }
3740 
3741 }
3742 
3743 }
3744 }
3745 }
3746 
3747 }
3748 
3749 }
3750 
3751 } else
3752 {
3753 IkReal x849=((IkReal(1.00000000000000))*(sj7));
3754 IkReal x850=((npy)*(sj8));
3755 IkReal x851=((cj8)*(npx));
3756 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
3757 evalcond[1]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(sj5))));
3758 evalcond[2]=((IkReal(0.235000000000000))+(((cj7)*(x850)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x851)))+(((IkReal(-1.00000000000000))*(npz)*(x849)))+(((IkReal(0.250000000000000))*(cj5))));
3759 evalcond[3]=((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x849)))+(((cj7)*(r22)))+(((r21)*(sj7)*(sj8))));
3760 evalcond[4]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x849)*(x851)))+(((cj7)*(npz)))+(((sj7)*(x850))));
3761 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 )
3762 {
3763 {
3764 IkReal dummyeval[1];
3765 IkReal gconst27;
3766 gconst27=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
3767 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
3768 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3769 {
3770 {
3771 IkReal dummyeval[1];
3772 IkReal gconst25;
3773 IkReal x852=(sj8)*(sj8);
3774 IkReal x853=(cj8)*(cj8);
3775 IkReal x854=((IkReal(1.00000000000000))*(r10));
3776 IkReal x855=((cj7)*(sj8));
3777 IkReal x856=((r00)*(r11));
3778 IkReal x857=((cj7)*(cj8));
3779 IkReal x858=((sj7)*(x852));
3780 IkReal x859=((sj7)*(x853));
3781 gconst25=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x854)*(x858)))+(((IkReal(-1.00000000000000))*(r01)*(x854)*(x859)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x857)))+(((x856)*(x859)))+(((x856)*(x858)))+(((r01)*(r12)*(x857)))+(((r00)*(r12)*(x855)))+(((IkReal(-1.00000000000000))*(r02)*(x854)*(x855)))));
3782 IkReal x860=(sj8)*(sj8);
3783 IkReal x861=(cj8)*(cj8);
3784 IkReal x862=((IkReal(1.00000000000000))*(r10));
3785 IkReal x863=((cj7)*(sj8));
3786 IkReal x864=((r00)*(r11));
3787 IkReal x865=((cj7)*(cj8));
3788 IkReal x866=((sj7)*(x860));
3789 IkReal x867=((sj7)*(x861));
3790 dummyeval[0]=((((IkReal(-1.00000000000000))*(r02)*(x862)*(x863)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x865)))+(((r01)*(r12)*(x865)))+(((IkReal(-1.00000000000000))*(r01)*(x862)*(x866)))+(((IkReal(-1.00000000000000))*(r01)*(x862)*(x867)))+(((r00)*(r12)*(x863)))+(((x864)*(x866)))+(((x864)*(x867))));
3791 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3792 {
3793 {
3794 IkReal dummyeval[1];
3795 IkReal gconst26;
3796 IkReal x868=(sj7)*(sj7);
3797 IkReal x869=(cj7)*(cj7);
3798 IkReal x870=((r02)*(r10));
3799 IkReal x871=((r01)*(r12));
3800 IkReal x872=((sj8)*(x868));
3801 IkReal x873=((IkReal(1.00000000000000))*(r02)*(r11));
3802 IkReal x874=((cj8)*(x869));
3803 IkReal x875=((IkReal(1.00000000000000))*(r00)*(r12));
3804 IkReal x876=((sj8)*(x869));
3805 IkReal x877=((cj8)*(x868));
3806 gconst26=IKsign(((((IkReal(-1.00000000000000))*(x872)*(x873)))+(((x871)*(x872)))+(((x871)*(x876)))+(((x870)*(x874)))+(((x870)*(x877)))+(((IkReal(-1.00000000000000))*(x873)*(x876)))+(((IkReal(-1.00000000000000))*(x875)*(x877)))+(((IkReal(-1.00000000000000))*(x874)*(x875)))));
3807 IkReal x878=(sj7)*(sj7);
3808 IkReal x879=(cj7)*(cj7);
3809 IkReal x880=((r02)*(r10));
3810 IkReal x881=((r01)*(r12));
3811 IkReal x882=((sj8)*(x878));
3812 IkReal x883=((IkReal(1.00000000000000))*(r02)*(r11));
3813 IkReal x884=((cj8)*(x879));
3814 IkReal x885=((IkReal(1.00000000000000))*(r00)*(r12));
3815 IkReal x886=((sj8)*(x879));
3816 IkReal x887=((cj8)*(x878));
3817 dummyeval[0]=((((IkReal(-1.00000000000000))*(x883)*(x886)))+(((x881)*(x886)))+(((x881)*(x882)))+(((IkReal(-1.00000000000000))*(x882)*(x883)))+(((x880)*(x887)))+(((x880)*(x884)))+(((IkReal(-1.00000000000000))*(x885)*(x887)))+(((IkReal(-1.00000000000000))*(x884)*(x885))));
3818 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3819 {
3820 continue;
3821 
3822 } else
3823 {
3824 {
3825 IkReal j3array[1], cj3array[1], sj3array[1];
3826 bool j3valid[1]={false};
3827 _nj3 = 1;
3828 IkReal x888=((cj7)*(cj8));
3829 IkReal x889=((IkReal(1.00000000000000))*(cj7)*(sj8));
3830 if( IKabs(((gconst26)*(((((r10)*(x888)))+(((IkReal(-1.00000000000000))*(r11)*(x889)))+(((r12)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst26)*(((((r00)*(x888)))+(((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x889))))))) < IKFAST_ATAN2_MAGTHRESH )
3831  continue;
3832 j3array[0]=IKatan2(((gconst26)*(((((r10)*(x888)))+(((IkReal(-1.00000000000000))*(r11)*(x889)))+(((r12)*(sj7)))))), ((gconst26)*(((((r00)*(x888)))+(((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x889)))))));
3833 sj3array[0]=IKsin(j3array[0]);
3834 cj3array[0]=IKcos(j3array[0]);
3835 if( j3array[0] > IKPI )
3836 {
3837  j3array[0]-=IK2PI;
3838 }
3839 else if( j3array[0] < -IKPI )
3840 { j3array[0]+=IK2PI;
3841 }
3842 j3valid[0] = true;
3843 for(int ij3 = 0; ij3 < 1; ++ij3)
3844 {
3845 if( !j3valid[ij3] )
3846 {
3847  continue;
3848 }
3849 _ij3[0] = ij3; _ij3[1] = -1;
3850 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
3851 {
3852 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
3853 {
3854  j3valid[iij3]=false; _ij3[1] = iij3; break;
3855 }
3856 }
3857 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
3858 {
3859 IkReal evalcond[4];
3860 IkReal x890=IKsin(j3);
3861 IkReal x891=IKcos(j3);
3862 IkReal x892=((r01)*(sj8));
3863 IkReal x893=((cj8)*(sj7));
3864 IkReal x894=((IkReal(1.00000000000000))*(sj7));
3865 IkReal x895=((IkReal(1.00000000000000))*(r12));
3866 IkReal x896=((r11)*(sj8));
3867 IkReal x897=((IkReal(1.00000000000000))*(r00));
3868 IkReal x898=((cj7)*(x890));
3869 IkReal x899=((r10)*(x891));
3870 IkReal x900=((IkReal(1.00000000000000))*(cj7)*(x891));
3871 evalcond[0]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x891)))+(((IkReal(-1.00000000000000))*(sj8)*(x899)))+(((r00)*(sj8)*(x890)))+(((cj8)*(r01)*(x890))));
3872 evalcond[1]=((((IkReal(-1.00000000000000))*(x896)*(x900)))+(((IkReal(-1.00000000000000))*(r02)*(x890)*(x894)))+(((r12)*(sj7)*(x891)))+(((cj7)*(cj8)*(x899)))+(((x892)*(x898)))+(((IkReal(-1.00000000000000))*(cj8)*(x897)*(x898))));
3873 evalcond[2]=((IkReal(-1.00000000000000))+(((r02)*(x898)))+(((sj7)*(x890)*(x892)))+(((IkReal(-1.00000000000000))*(x891)*(x894)*(x896)))+(((IkReal(-1.00000000000000))*(x890)*(x893)*(x897)))+(((x893)*(x899)))+(((IkReal(-1.00000000000000))*(cj7)*(x891)*(x895))));
3874 evalcond[3]=((((r00)*(x891)*(x893)))+(((IkReal(-1.00000000000000))*(x895)*(x898)))+(((r10)*(x890)*(x893)))+(((IkReal(-1.00000000000000))*(x890)*(x894)*(x896)))+(((IkReal(-1.00000000000000))*(x891)*(x892)*(x894)))+(((IkReal(-1.00000000000000))*(r02)*(x900))));
3875 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
3876 {
3877 continue;
3878 }
3879 }
3880 
3881 {
3882 IkReal dummyeval[1];
3883 IkReal gconst28;
3884 gconst28=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
3885 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
3886 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3887 {
3888 {
3889 IkReal dummyeval[1];
3890 IkReal gconst29;
3891 gconst29=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
3892 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
3893 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
3894 {
3895 continue;
3896 
3897 } else
3898 {
3899 {
3900 IkReal j4array[1], cj4array[1], sj4array[1];
3901 bool j4valid[1]={false};
3902 _nj4 = 1;
3903 IkReal x901=((IkReal(1.00000000000000))*(sj5));
3904 IkReal x902=((r20)*(sj8));
3905 IkReal x903=((cj5)*(cj8));
3906 IkReal x904=((r11)*(sj3));
3907 IkReal x905=((cj3)*(r01));
3908 IkReal x906=((cj3)*(r00)*(sj8));
3909 IkReal x907=((r10)*(sj3)*(sj8));
3910 if( IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(r21)*(x903)))+(((IkReal(-1.00000000000000))*(x901)*(x906)))+(((IkReal(-1.00000000000000))*(x901)*(x907)))+(((IkReal(-1.00000000000000))*(cj5)*(x902)))+(((IkReal(-1.00000000000000))*(cj8)*(x901)*(x905)))+(((IkReal(-1.00000000000000))*(cj8)*(x901)*(x904))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst29)*(((((x903)*(x905)))+(((x903)*(x904)))+(((cj5)*(x907)))+(((cj5)*(x906)))+(((IkReal(-1.00000000000000))*(x901)*(x902)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x901))))))) < IKFAST_ATAN2_MAGTHRESH )
3911  continue;
3912 j4array[0]=IKatan2(((gconst29)*(((((IkReal(-1.00000000000000))*(r21)*(x903)))+(((IkReal(-1.00000000000000))*(x901)*(x906)))+(((IkReal(-1.00000000000000))*(x901)*(x907)))+(((IkReal(-1.00000000000000))*(cj5)*(x902)))+(((IkReal(-1.00000000000000))*(cj8)*(x901)*(x905)))+(((IkReal(-1.00000000000000))*(cj8)*(x901)*(x904)))))), ((gconst29)*(((((x903)*(x905)))+(((x903)*(x904)))+(((cj5)*(x907)))+(((cj5)*(x906)))+(((IkReal(-1.00000000000000))*(x901)*(x902)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x901)))))));
3913 sj4array[0]=IKsin(j4array[0]);
3914 cj4array[0]=IKcos(j4array[0]);
3915 if( j4array[0] > IKPI )
3916 {
3917  j4array[0]-=IK2PI;
3918 }
3919 else if( j4array[0] < -IKPI )
3920 { j4array[0]+=IK2PI;
3921 }
3922 j4valid[0] = true;
3923 for(int ij4 = 0; ij4 < 1; ++ij4)
3924 {
3925 if( !j4valid[ij4] )
3926 {
3927  continue;
3928 }
3929 _ij4[0] = ij4; _ij4[1] = -1;
3930 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
3931 {
3932 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
3933 {
3934  j4valid[iij4]=false; _ij4[1] = iij4; break;
3935 }
3936 }
3937 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
3938 {
3939 IkReal evalcond[4];
3940 IkReal x908=IKsin(j4);
3941 IkReal x909=IKcos(j4);
3942 IkReal x910=((IkReal(1.00000000000000))*(cj8));
3943 IkReal x911=((cj3)*(r01));
3944 IkReal x912=((cj3)*(r00));
3945 IkReal x913=((cj7)*(cj8));
3946 IkReal x914=((r11)*(sj3));
3947 IkReal x915=((IkReal(1.00000000000000))*(sj8));
3948 IkReal x916=((r10)*(sj3));
3949 IkReal x917=((sj5)*(x909));
3950 IkReal x918=((cj5)*(x908));
3951 IkReal x919=((cj5)*(x909));
3952 IkReal x920=((sj5)*(x908));
3953 IkReal x921=((x918)+(x917));
3954 evalcond[0]=((((cj8)*(r21)))+(x921)+(((r20)*(sj8))));
3955 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x910)))+(((IkReal(-1.00000000000000))*(x919)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x920)+(((cj7)*(r21)*(sj8))));
3956 evalcond[2]=((((IkReal(-1.00000000000000))*(x920)))+(((IkReal(-1.00000000000000))*(x910)*(x911)))+(((IkReal(-1.00000000000000))*(x910)*(x914)))+(((IkReal(-1.00000000000000))*(x912)*(x915)))+(x919)+(((IkReal(-1.00000000000000))*(x915)*(x916))));
3957 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x911)*(x915)))+(((cj3)*(r02)*(sj7)))+(((x912)*(x913)))+(((x913)*(x916)))+(x921)+(((IkReal(-1.00000000000000))*(cj7)*(x914)*(x915))));
3958 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
3959 {
3960 continue;
3961 }
3962 }
3963 
3964 {
3965 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3966 vinfos[0].jointtype = 1;
3967 vinfos[0].foffset = j3;
3968 vinfos[0].indices[0] = _ij3[0];
3969 vinfos[0].indices[1] = _ij3[1];
3970 vinfos[0].maxsolutions = _nj3;
3971 vinfos[1].jointtype = 1;
3972 vinfos[1].foffset = j4;
3973 vinfos[1].indices[0] = _ij4[0];
3974 vinfos[1].indices[1] = _ij4[1];
3975 vinfos[1].maxsolutions = _nj4;
3976 vinfos[2].jointtype = 1;
3977 vinfos[2].foffset = j5;
3978 vinfos[2].indices[0] = _ij5[0];
3979 vinfos[2].indices[1] = _ij5[1];
3980 vinfos[2].maxsolutions = _nj5;
3981 vinfos[3].jointtype = 1;
3982 vinfos[3].foffset = j6;
3983 vinfos[3].indices[0] = _ij6[0];
3984 vinfos[3].indices[1] = _ij6[1];
3985 vinfos[3].maxsolutions = _nj6;
3986 vinfos[4].jointtype = 1;
3987 vinfos[4].foffset = j7;
3988 vinfos[4].indices[0] = _ij7[0];
3989 vinfos[4].indices[1] = _ij7[1];
3990 vinfos[4].maxsolutions = _nj7;
3991 vinfos[5].jointtype = 1;
3992 vinfos[5].foffset = j8;
3993 vinfos[5].indices[0] = _ij8[0];
3994 vinfos[5].indices[1] = _ij8[1];
3995 vinfos[5].maxsolutions = _nj8;
3996 std::vector<int> vfree(0);
3997 solutions.AddSolution(vinfos,vfree);
3998 }
3999 }
4000 }
4001 
4002 }
4003 
4004 }
4005 
4006 } else
4007 {
4008 {
4009 IkReal j4array[1], cj4array[1], sj4array[1];
4010 bool j4valid[1]={false};
4011 _nj4 = 1;
4012 IkReal x922=((r22)*(sj7));
4013 IkReal x923=((cj8)*(sj5));
4014 IkReal x924=((sj5)*(sj8));
4015 IkReal x925=((cj7)*(r20));
4016 IkReal x926=((cj5)*(cj8));
4017 IkReal x927=((cj7)*(r21));
4018 IkReal x928=((cj5)*(sj8));
4019 if( IKabs(((gconst28)*(((((IkReal(-1.00000000000000))*(sj5)*(x922)))+(((x924)*(x927)))+(((r21)*(x926)))+(((IkReal(-1.00000000000000))*(x923)*(x925)))+(((r20)*(x928))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst28)*(((((IkReal(-1.00000000000000))*(x927)*(x928)))+(((r21)*(x923)))+(((r20)*(x924)))+(((x925)*(x926)))+(((cj5)*(x922))))))) < IKFAST_ATAN2_MAGTHRESH )
4020  continue;
4021 j4array[0]=IKatan2(((gconst28)*(((((IkReal(-1.00000000000000))*(sj5)*(x922)))+(((x924)*(x927)))+(((r21)*(x926)))+(((IkReal(-1.00000000000000))*(x923)*(x925)))+(((r20)*(x928)))))), ((gconst28)*(((((IkReal(-1.00000000000000))*(x927)*(x928)))+(((r21)*(x923)))+(((r20)*(x924)))+(((x925)*(x926)))+(((cj5)*(x922)))))));
4022 sj4array[0]=IKsin(j4array[0]);
4023 cj4array[0]=IKcos(j4array[0]);
4024 if( j4array[0] > IKPI )
4025 {
4026  j4array[0]-=IK2PI;
4027 }
4028 else if( j4array[0] < -IKPI )
4029 { j4array[0]+=IK2PI;
4030 }
4031 j4valid[0] = true;
4032 for(int ij4 = 0; ij4 < 1; ++ij4)
4033 {
4034 if( !j4valid[ij4] )
4035 {
4036  continue;
4037 }
4038 _ij4[0] = ij4; _ij4[1] = -1;
4039 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
4040 {
4041 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
4042 {
4043  j4valid[iij4]=false; _ij4[1] = iij4; break;
4044 }
4045 }
4046 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
4047 {
4048 IkReal evalcond[4];
4049 IkReal x929=IKsin(j4);
4050 IkReal x930=IKcos(j4);
4051 IkReal x931=((IkReal(1.00000000000000))*(cj8));
4052 IkReal x932=((cj3)*(r01));
4053 IkReal x933=((cj3)*(r00));
4054 IkReal x934=((cj7)*(cj8));
4055 IkReal x935=((r11)*(sj3));
4056 IkReal x936=((IkReal(1.00000000000000))*(sj8));
4057 IkReal x937=((r10)*(sj3));
4058 IkReal x938=((sj5)*(x930));
4059 IkReal x939=((cj5)*(x929));
4060 IkReal x940=((cj5)*(x930));
4061 IkReal x941=((sj5)*(x929));
4062 IkReal x942=((x939)+(x938));
4063 evalcond[0]=((((cj8)*(r21)))+(x942)+(((r20)*(sj8))));
4064 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x931)))+(((IkReal(-1.00000000000000))*(x940)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x941)+(((cj7)*(r21)*(sj8))));
4065 evalcond[2]=((((IkReal(-1.00000000000000))*(x931)*(x932)))+(((IkReal(-1.00000000000000))*(x931)*(x935)))+(((IkReal(-1.00000000000000))*(x941)))+(((IkReal(-1.00000000000000))*(x936)*(x937)))+(((IkReal(-1.00000000000000))*(x933)*(x936)))+(x940));
4066 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x932)*(x936)))+(((IkReal(-1.00000000000000))*(cj7)*(x935)*(x936)))+(((cj3)*(r02)*(sj7)))+(((x934)*(x937)))+(x942)+(((x933)*(x934))));
4067 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
4068 {
4069 continue;
4070 }
4071 }
4072 
4073 {
4074 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4075 vinfos[0].jointtype = 1;
4076 vinfos[0].foffset = j3;
4077 vinfos[0].indices[0] = _ij3[0];
4078 vinfos[0].indices[1] = _ij3[1];
4079 vinfos[0].maxsolutions = _nj3;
4080 vinfos[1].jointtype = 1;
4081 vinfos[1].foffset = j4;
4082 vinfos[1].indices[0] = _ij4[0];
4083 vinfos[1].indices[1] = _ij4[1];
4084 vinfos[1].maxsolutions = _nj4;
4085 vinfos[2].jointtype = 1;
4086 vinfos[2].foffset = j5;
4087 vinfos[2].indices[0] = _ij5[0];
4088 vinfos[2].indices[1] = _ij5[1];
4089 vinfos[2].maxsolutions = _nj5;
4090 vinfos[3].jointtype = 1;
4091 vinfos[3].foffset = j6;
4092 vinfos[3].indices[0] = _ij6[0];
4093 vinfos[3].indices[1] = _ij6[1];
4094 vinfos[3].maxsolutions = _nj6;
4095 vinfos[4].jointtype = 1;
4096 vinfos[4].foffset = j7;
4097 vinfos[4].indices[0] = _ij7[0];
4098 vinfos[4].indices[1] = _ij7[1];
4099 vinfos[4].maxsolutions = _nj7;
4100 vinfos[5].jointtype = 1;
4101 vinfos[5].foffset = j8;
4102 vinfos[5].indices[0] = _ij8[0];
4103 vinfos[5].indices[1] = _ij8[1];
4104 vinfos[5].maxsolutions = _nj8;
4105 std::vector<int> vfree(0);
4106 solutions.AddSolution(vinfos,vfree);
4107 }
4108 }
4109 }
4110 
4111 }
4112 
4113 }
4114 }
4115 }
4116 
4117 }
4118 
4119 }
4120 
4121 } else
4122 {
4123 {
4124 IkReal j3array[1], cj3array[1], sj3array[1];
4125 bool j3valid[1]={false};
4126 _nj3 = 1;
4127 IkReal x943=((IkReal(1.00000000000000))*(cj8));
4128 IkReal x944=((IkReal(1.00000000000000))*(sj8));
4129 if( IKabs(((gconst25)*(((((IkReal(-1.00000000000000))*(r11)*(x943)))+(((IkReal(-1.00000000000000))*(r10)*(x944))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst25)*(((((IkReal(-1.00000000000000))*(r01)*(x943)))+(((IkReal(-1.00000000000000))*(r00)*(x944))))))) < IKFAST_ATAN2_MAGTHRESH )
4130  continue;
4131 j3array[0]=IKatan2(((gconst25)*(((((IkReal(-1.00000000000000))*(r11)*(x943)))+(((IkReal(-1.00000000000000))*(r10)*(x944)))))), ((gconst25)*(((((IkReal(-1.00000000000000))*(r01)*(x943)))+(((IkReal(-1.00000000000000))*(r00)*(x944)))))));
4132 sj3array[0]=IKsin(j3array[0]);
4133 cj3array[0]=IKcos(j3array[0]);
4134 if( j3array[0] > IKPI )
4135 {
4136  j3array[0]-=IK2PI;
4137 }
4138 else if( j3array[0] < -IKPI )
4139 { j3array[0]+=IK2PI;
4140 }
4141 j3valid[0] = true;
4142 for(int ij3 = 0; ij3 < 1; ++ij3)
4143 {
4144 if( !j3valid[ij3] )
4145 {
4146  continue;
4147 }
4148 _ij3[0] = ij3; _ij3[1] = -1;
4149 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
4150 {
4151 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
4152 {
4153  j3valid[iij3]=false; _ij3[1] = iij3; break;
4154 }
4155 }
4156 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
4157 {
4158 IkReal evalcond[4];
4159 IkReal x945=IKsin(j3);
4160 IkReal x946=IKcos(j3);
4161 IkReal x947=((r01)*(sj8));
4162 IkReal x948=((cj8)*(sj7));
4163 IkReal x949=((IkReal(1.00000000000000))*(sj7));
4164 IkReal x950=((IkReal(1.00000000000000))*(r12));
4165 IkReal x951=((r11)*(sj8));
4166 IkReal x952=((IkReal(1.00000000000000))*(r00));
4167 IkReal x953=((cj7)*(x945));
4168 IkReal x954=((r10)*(x946));
4169 IkReal x955=((IkReal(1.00000000000000))*(cj7)*(x946));
4170 evalcond[0]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x946)))+(((cj8)*(r01)*(x945)))+(((r00)*(sj8)*(x945)))+(((IkReal(-1.00000000000000))*(sj8)*(x954))));
4171 evalcond[1]=((((IkReal(-1.00000000000000))*(r02)*(x945)*(x949)))+(((cj7)*(cj8)*(x954)))+(((IkReal(-1.00000000000000))*(cj8)*(x952)*(x953)))+(((x947)*(x953)))+(((r12)*(sj7)*(x946)))+(((IkReal(-1.00000000000000))*(x951)*(x955))));
4172 evalcond[2]=((IkReal(-1.00000000000000))+(((sj7)*(x945)*(x947)))+(((x948)*(x954)))+(((IkReal(-1.00000000000000))*(cj7)*(x946)*(x950)))+(((IkReal(-1.00000000000000))*(x946)*(x949)*(x951)))+(((r02)*(x953)))+(((IkReal(-1.00000000000000))*(x945)*(x948)*(x952))));
4173 evalcond[3]=((((r00)*(x946)*(x948)))+(((IkReal(-1.00000000000000))*(x946)*(x947)*(x949)))+(((IkReal(-1.00000000000000))*(x950)*(x953)))+(((r10)*(x945)*(x948)))+(((IkReal(-1.00000000000000))*(r02)*(x955)))+(((IkReal(-1.00000000000000))*(x945)*(x949)*(x951))));
4174 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
4175 {
4176 continue;
4177 }
4178 }
4179 
4180 {
4181 IkReal dummyeval[1];
4182 IkReal gconst28;
4183 gconst28=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
4184 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
4185 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4186 {
4187 {
4188 IkReal dummyeval[1];
4189 IkReal gconst29;
4190 gconst29=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
4191 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
4192 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4193 {
4194 continue;
4195 
4196 } else
4197 {
4198 {
4199 IkReal j4array[1], cj4array[1], sj4array[1];
4200 bool j4valid[1]={false};
4201 _nj4 = 1;
4202 IkReal x956=((IkReal(1.00000000000000))*(sj5));
4203 IkReal x957=((r20)*(sj8));
4204 IkReal x958=((cj5)*(cj8));
4205 IkReal x959=((r11)*(sj3));
4206 IkReal x960=((cj3)*(r01));
4207 IkReal x961=((cj3)*(r00)*(sj8));
4208 IkReal x962=((r10)*(sj3)*(sj8));
4209 if( IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(cj8)*(x956)*(x959)))+(((IkReal(-1.00000000000000))*(cj8)*(x956)*(x960)))+(((IkReal(-1.00000000000000))*(x956)*(x962)))+(((IkReal(-1.00000000000000))*(x956)*(x961)))+(((IkReal(-1.00000000000000))*(cj5)*(x957)))+(((IkReal(-1.00000000000000))*(r21)*(x958))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(x956)*(x957)))+(((x958)*(x959)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x956)))+(((x958)*(x960)))+(((cj5)*(x961)))+(((cj5)*(x962))))))) < IKFAST_ATAN2_MAGTHRESH )
4210  continue;
4211 j4array[0]=IKatan2(((gconst29)*(((((IkReal(-1.00000000000000))*(cj8)*(x956)*(x959)))+(((IkReal(-1.00000000000000))*(cj8)*(x956)*(x960)))+(((IkReal(-1.00000000000000))*(x956)*(x962)))+(((IkReal(-1.00000000000000))*(x956)*(x961)))+(((IkReal(-1.00000000000000))*(cj5)*(x957)))+(((IkReal(-1.00000000000000))*(r21)*(x958)))))), ((gconst29)*(((((IkReal(-1.00000000000000))*(x956)*(x957)))+(((x958)*(x959)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x956)))+(((x958)*(x960)))+(((cj5)*(x961)))+(((cj5)*(x962)))))));
4212 sj4array[0]=IKsin(j4array[0]);
4213 cj4array[0]=IKcos(j4array[0]);
4214 if( j4array[0] > IKPI )
4215 {
4216  j4array[0]-=IK2PI;
4217 }
4218 else if( j4array[0] < -IKPI )
4219 { j4array[0]+=IK2PI;
4220 }
4221 j4valid[0] = true;
4222 for(int ij4 = 0; ij4 < 1; ++ij4)
4223 {
4224 if( !j4valid[ij4] )
4225 {
4226  continue;
4227 }
4228 _ij4[0] = ij4; _ij4[1] = -1;
4229 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
4230 {
4231 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
4232 {
4233  j4valid[iij4]=false; _ij4[1] = iij4; break;
4234 }
4235 }
4236 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
4237 {
4238 IkReal evalcond[4];
4239 IkReal x963=IKsin(j4);
4240 IkReal x964=IKcos(j4);
4241 IkReal x965=((IkReal(1.00000000000000))*(cj8));
4242 IkReal x966=((cj3)*(r01));
4243 IkReal x967=((cj3)*(r00));
4244 IkReal x968=((cj7)*(cj8));
4245 IkReal x969=((r11)*(sj3));
4246 IkReal x970=((IkReal(1.00000000000000))*(sj8));
4247 IkReal x971=((r10)*(sj3));
4248 IkReal x972=((sj5)*(x964));
4249 IkReal x973=((cj5)*(x963));
4250 IkReal x974=((cj5)*(x964));
4251 IkReal x975=((sj5)*(x963));
4252 IkReal x976=((x973)+(x972));
4253 evalcond[0]=((((cj8)*(r21)))+(x976)+(((r20)*(sj8))));
4254 evalcond[1]=((((IkReal(-1.00000000000000))*(x974)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x975)+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x965))));
4255 evalcond[2]=((((IkReal(-1.00000000000000))*(x975)))+(((IkReal(-1.00000000000000))*(x965)*(x969)))+(((IkReal(-1.00000000000000))*(x965)*(x966)))+(((IkReal(-1.00000000000000))*(x967)*(x970)))+(((IkReal(-1.00000000000000))*(x970)*(x971)))+(x974));
4256 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x968)*(x971)))+(((IkReal(-1.00000000000000))*(cj7)*(x969)*(x970)))+(((x967)*(x968)))+(((cj3)*(r02)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x966)*(x970)))+(x976));
4257 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
4258 {
4259 continue;
4260 }
4261 }
4262 
4263 {
4264 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4265 vinfos[0].jointtype = 1;
4266 vinfos[0].foffset = j3;
4267 vinfos[0].indices[0] = _ij3[0];
4268 vinfos[0].indices[1] = _ij3[1];
4269 vinfos[0].maxsolutions = _nj3;
4270 vinfos[1].jointtype = 1;
4271 vinfos[1].foffset = j4;
4272 vinfos[1].indices[0] = _ij4[0];
4273 vinfos[1].indices[1] = _ij4[1];
4274 vinfos[1].maxsolutions = _nj4;
4275 vinfos[2].jointtype = 1;
4276 vinfos[2].foffset = j5;
4277 vinfos[2].indices[0] = _ij5[0];
4278 vinfos[2].indices[1] = _ij5[1];
4279 vinfos[2].maxsolutions = _nj5;
4280 vinfos[3].jointtype = 1;
4281 vinfos[3].foffset = j6;
4282 vinfos[3].indices[0] = _ij6[0];
4283 vinfos[3].indices[1] = _ij6[1];
4284 vinfos[3].maxsolutions = _nj6;
4285 vinfos[4].jointtype = 1;
4286 vinfos[4].foffset = j7;
4287 vinfos[4].indices[0] = _ij7[0];
4288 vinfos[4].indices[1] = _ij7[1];
4289 vinfos[4].maxsolutions = _nj7;
4290 vinfos[5].jointtype = 1;
4291 vinfos[5].foffset = j8;
4292 vinfos[5].indices[0] = _ij8[0];
4293 vinfos[5].indices[1] = _ij8[1];
4294 vinfos[5].maxsolutions = _nj8;
4295 std::vector<int> vfree(0);
4296 solutions.AddSolution(vinfos,vfree);
4297 }
4298 }
4299 }
4300 
4301 }
4302 
4303 }
4304 
4305 } else
4306 {
4307 {
4308 IkReal j4array[1], cj4array[1], sj4array[1];
4309 bool j4valid[1]={false};
4310 _nj4 = 1;
4311 IkReal x977=((r22)*(sj7));
4312 IkReal x978=((cj8)*(sj5));
4313 IkReal x979=((sj5)*(sj8));
4314 IkReal x980=((cj7)*(r20));
4315 IkReal x981=((cj5)*(cj8));
4316 IkReal x982=((cj7)*(r21));
4317 IkReal x983=((cj5)*(sj8));
4318 if( IKabs(((gconst28)*(((((r21)*(x981)))+(((IkReal(-1.00000000000000))*(x978)*(x980)))+(((x979)*(x982)))+(((IkReal(-1.00000000000000))*(sj5)*(x977)))+(((r20)*(x983))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst28)*(((((IkReal(-1.00000000000000))*(x982)*(x983)))+(((cj5)*(x977)))+(((r21)*(x978)))+(((r20)*(x979)))+(((x980)*(x981))))))) < IKFAST_ATAN2_MAGTHRESH )
4319  continue;
4320 j4array[0]=IKatan2(((gconst28)*(((((r21)*(x981)))+(((IkReal(-1.00000000000000))*(x978)*(x980)))+(((x979)*(x982)))+(((IkReal(-1.00000000000000))*(sj5)*(x977)))+(((r20)*(x983)))))), ((gconst28)*(((((IkReal(-1.00000000000000))*(x982)*(x983)))+(((cj5)*(x977)))+(((r21)*(x978)))+(((r20)*(x979)))+(((x980)*(x981)))))));
4321 sj4array[0]=IKsin(j4array[0]);
4322 cj4array[0]=IKcos(j4array[0]);
4323 if( j4array[0] > IKPI )
4324 {
4325  j4array[0]-=IK2PI;
4326 }
4327 else if( j4array[0] < -IKPI )
4328 { j4array[0]+=IK2PI;
4329 }
4330 j4valid[0] = true;
4331 for(int ij4 = 0; ij4 < 1; ++ij4)
4332 {
4333 if( !j4valid[ij4] )
4334 {
4335  continue;
4336 }
4337 _ij4[0] = ij4; _ij4[1] = -1;
4338 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
4339 {
4340 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
4341 {
4342  j4valid[iij4]=false; _ij4[1] = iij4; break;
4343 }
4344 }
4345 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
4346 {
4347 IkReal evalcond[4];
4348 IkReal x984=IKsin(j4);
4349 IkReal x985=IKcos(j4);
4350 IkReal x986=((IkReal(1.00000000000000))*(cj8));
4351 IkReal x987=((cj3)*(r01));
4352 IkReal x988=((cj3)*(r00));
4353 IkReal x989=((cj7)*(cj8));
4354 IkReal x990=((r11)*(sj3));
4355 IkReal x991=((IkReal(1.00000000000000))*(sj8));
4356 IkReal x992=((r10)*(sj3));
4357 IkReal x993=((sj5)*(x985));
4358 IkReal x994=((cj5)*(x984));
4359 IkReal x995=((cj5)*(x985));
4360 IkReal x996=((sj5)*(x984));
4361 IkReal x997=((x993)+(x994));
4362 evalcond[0]=((((cj8)*(r21)))+(x997)+(((r20)*(sj8))));
4363 evalcond[1]=((((IkReal(-1.00000000000000))*(x995)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x986)))+(x996)+(((cj7)*(r21)*(sj8))));
4364 evalcond[2]=((((IkReal(-1.00000000000000))*(x996)))+(((IkReal(-1.00000000000000))*(x991)*(x992)))+(((IkReal(-1.00000000000000))*(x986)*(x987)))+(x995)+(((IkReal(-1.00000000000000))*(x986)*(x990)))+(((IkReal(-1.00000000000000))*(x988)*(x991))));
4365 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x989)*(x992)))+(((x988)*(x989)))+(((IkReal(-1.00000000000000))*(cj7)*(x987)*(x991)))+(((IkReal(-1.00000000000000))*(cj7)*(x990)*(x991)))+(((cj3)*(r02)*(sj7)))+(x997));
4366 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
4367 {
4368 continue;
4369 }
4370 }
4371 
4372 {
4373 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4374 vinfos[0].jointtype = 1;
4375 vinfos[0].foffset = j3;
4376 vinfos[0].indices[0] = _ij3[0];
4377 vinfos[0].indices[1] = _ij3[1];
4378 vinfos[0].maxsolutions = _nj3;
4379 vinfos[1].jointtype = 1;
4380 vinfos[1].foffset = j4;
4381 vinfos[1].indices[0] = _ij4[0];
4382 vinfos[1].indices[1] = _ij4[1];
4383 vinfos[1].maxsolutions = _nj4;
4384 vinfos[2].jointtype = 1;
4385 vinfos[2].foffset = j5;
4386 vinfos[2].indices[0] = _ij5[0];
4387 vinfos[2].indices[1] = _ij5[1];
4388 vinfos[2].maxsolutions = _nj5;
4389 vinfos[3].jointtype = 1;
4390 vinfos[3].foffset = j6;
4391 vinfos[3].indices[0] = _ij6[0];
4392 vinfos[3].indices[1] = _ij6[1];
4393 vinfos[3].maxsolutions = _nj6;
4394 vinfos[4].jointtype = 1;
4395 vinfos[4].foffset = j7;
4396 vinfos[4].indices[0] = _ij7[0];
4397 vinfos[4].indices[1] = _ij7[1];
4398 vinfos[4].maxsolutions = _nj7;
4399 vinfos[5].jointtype = 1;
4400 vinfos[5].foffset = j8;
4401 vinfos[5].indices[0] = _ij8[0];
4402 vinfos[5].indices[1] = _ij8[1];
4403 vinfos[5].maxsolutions = _nj8;
4404 std::vector<int> vfree(0);
4405 solutions.AddSolution(vinfos,vfree);
4406 }
4407 }
4408 }
4409 
4410 }
4411 
4412 }
4413 }
4414 }
4415 
4416 }
4417 
4418 }
4419 
4420 } else
4421 {
4422 {
4423 IkReal j4array[1], cj4array[1], sj4array[1];
4424 bool j4valid[1]={false};
4425 _nj4 = 1;
4426 IkReal x998=((cj8)*(r21));
4427 IkReal x999=((r22)*(sj7));
4428 IkReal x1000=((sj5)*(sj8));
4429 IkReal x1001=((IkReal(1.00000000000000))*(sj5));
4430 IkReal x1002=((cj5)*(cj7));
4431 IkReal x1003=((cj8)*(r20));
4432 if( IKabs(((gconst27)*(((((IkReal(-1.00000000000000))*(cj7)*(x1001)*(x1003)))+(((cj5)*(x998)))+(((cj5)*(r20)*(sj8)))+(((IkReal(-1.00000000000000))*(x1001)*(x999)))+(((cj7)*(r21)*(x1000))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst27)*(((((cj5)*(x999)))+(((sj5)*(x998)))+(((r20)*(x1000)))+(((x1002)*(x1003)))+(((IkReal(-1.00000000000000))*(r21)*(sj8)*(x1002))))))) < IKFAST_ATAN2_MAGTHRESH )
4433  continue;
4434 j4array[0]=IKatan2(((gconst27)*(((((IkReal(-1.00000000000000))*(cj7)*(x1001)*(x1003)))+(((cj5)*(x998)))+(((cj5)*(r20)*(sj8)))+(((IkReal(-1.00000000000000))*(x1001)*(x999)))+(((cj7)*(r21)*(x1000)))))), ((gconst27)*(((((cj5)*(x999)))+(((sj5)*(x998)))+(((r20)*(x1000)))+(((x1002)*(x1003)))+(((IkReal(-1.00000000000000))*(r21)*(sj8)*(x1002)))))));
4435 sj4array[0]=IKsin(j4array[0]);
4436 cj4array[0]=IKcos(j4array[0]);
4437 if( j4array[0] > IKPI )
4438 {
4439  j4array[0]-=IK2PI;
4440 }
4441 else if( j4array[0] < -IKPI )
4442 { j4array[0]+=IK2PI;
4443 }
4444 j4valid[0] = true;
4445 for(int ij4 = 0; ij4 < 1; ++ij4)
4446 {
4447 if( !j4valid[ij4] )
4448 {
4449  continue;
4450 }
4451 _ij4[0] = ij4; _ij4[1] = -1;
4452 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
4453 {
4454 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
4455 {
4456  j4valid[iij4]=false; _ij4[1] = iij4; break;
4457 }
4458 }
4459 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
4460 {
4461 IkReal evalcond[2];
4462 IkReal x1004=IKsin(j4);
4463 IkReal x1005=IKcos(j4);
4464 evalcond[0]=((((cj8)*(r21)))+(((cj5)*(x1004)))+(((sj5)*(x1005)))+(((r20)*(sj8))));
4465 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(cj8)*(r20)))+(((sj5)*(x1004)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj5)*(x1005)))+(((cj7)*(r21)*(sj8))));
4466 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
4467 {
4468 continue;
4469 }
4470 }
4471 
4472 {
4473 IkReal dummyeval[1];
4474 IkReal gconst31;
4475 IkReal x1006=(sj8)*(sj8);
4476 IkReal x1007=(cj8)*(cj8);
4477 IkReal x1008=((IkReal(1.00000000000000))*(r10));
4478 IkReal x1009=((cj7)*(sj8));
4479 IkReal x1010=((r00)*(r11));
4480 IkReal x1011=((cj7)*(cj8));
4481 IkReal x1012=((sj7)*(x1006));
4482 IkReal x1013=((sj7)*(x1007));
4483 gconst31=IKsign(((((r01)*(r12)*(x1011)))+(((r00)*(r12)*(x1009)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1011)))+(((IkReal(-1.00000000000000))*(r01)*(x1008)*(x1013)))+(((IkReal(-1.00000000000000))*(r01)*(x1008)*(x1012)))+(((x1010)*(x1013)))+(((x1010)*(x1012)))+(((IkReal(-1.00000000000000))*(r02)*(x1008)*(x1009)))));
4484 IkReal x1014=(sj8)*(sj8);
4485 IkReal x1015=(cj8)*(cj8);
4486 IkReal x1016=((IkReal(1.00000000000000))*(r10));
4487 IkReal x1017=((cj7)*(sj8));
4488 IkReal x1018=((r00)*(r11));
4489 IkReal x1019=((cj7)*(cj8));
4490 IkReal x1020=((sj7)*(x1014));
4491 IkReal x1021=((sj7)*(x1015));
4492 dummyeval[0]=((((IkReal(-1.00000000000000))*(r01)*(x1016)*(x1021)))+(((IkReal(-1.00000000000000))*(r01)*(x1016)*(x1020)))+(((r01)*(r12)*(x1019)))+(((r00)*(r12)*(x1017)))+(((x1018)*(x1021)))+(((x1018)*(x1020)))+(((IkReal(-1.00000000000000))*(r02)*(x1016)*(x1017)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1019))));
4493 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4494 {
4495 {
4496 IkReal dummyeval[1];
4497 IkReal gconst30;
4498 IkReal x1022=(cj8)*(cj8);
4499 IkReal x1023=(sj8)*(sj8);
4500 IkReal x1024=((IkReal(2.00000000000000))*(cj8)*(sj8));
4501 IkReal x1025=((IkReal(1.00000000000000))*(x1022));
4502 IkReal x1026=((IkReal(1.00000000000000))*(x1023));
4503 gconst30=IKsign(((((IkReal(-1.00000000000000))*(x1025)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1026)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1024)))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1024)))+(((IkReal(-1.00000000000000))*(x1026)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1025)*((r11)*(r11))))));
4504 IkReal x1027=(cj8)*(cj8);
4505 IkReal x1028=(sj8)*(sj8);
4506 IkReal x1029=((IkReal(2.00000000000000))*(cj8)*(sj8));
4507 IkReal x1030=((IkReal(1.00000000000000))*(x1027));
4508 IkReal x1031=((IkReal(1.00000000000000))*(x1028));
4509 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1030)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1030)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1029)))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1029)))+(((IkReal(-1.00000000000000))*(x1031)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1031)*((r10)*(r10)))));
4510 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4511 {
4512 continue;
4513 
4514 } else
4515 {
4516 {
4517 IkReal j3array[1], cj3array[1], sj3array[1];
4518 bool j3valid[1]={false};
4519 _nj3 = 1;
4520 IkReal x1032=((sj4)*(sj5));
4521 IkReal x1033=((r10)*(sj8));
4522 IkReal x1034=((cj8)*(r11));
4523 IkReal x1035=((cj8)*(r01));
4524 IkReal x1036=((r00)*(sj8));
4525 IkReal x1037=((IkReal(1.00000000000000))*(cj4)*(cj5));
4526 if( IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(x1033)*(x1037)))+(((IkReal(-1.00000000000000))*(x1034)*(x1037)))+(((x1032)*(x1034)))+(((x1032)*(x1033))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(x1035)*(x1037)))+(((IkReal(-1.00000000000000))*(x1036)*(x1037)))+(((x1032)*(x1035)))+(((x1032)*(x1036))))))) < IKFAST_ATAN2_MAGTHRESH )
4527  continue;
4528 j3array[0]=IKatan2(((gconst30)*(((((IkReal(-1.00000000000000))*(x1033)*(x1037)))+(((IkReal(-1.00000000000000))*(x1034)*(x1037)))+(((x1032)*(x1034)))+(((x1032)*(x1033)))))), ((gconst30)*(((((IkReal(-1.00000000000000))*(x1035)*(x1037)))+(((IkReal(-1.00000000000000))*(x1036)*(x1037)))+(((x1032)*(x1035)))+(((x1032)*(x1036)))))));
4529 sj3array[0]=IKsin(j3array[0]);
4530 cj3array[0]=IKcos(j3array[0]);
4531 if( j3array[0] > IKPI )
4532 {
4533  j3array[0]-=IK2PI;
4534 }
4535 else if( j3array[0] < -IKPI )
4536 { j3array[0]+=IK2PI;
4537 }
4538 j3valid[0] = true;
4539 for(int ij3 = 0; ij3 < 1; ++ij3)
4540 {
4541 if( !j3valid[ij3] )
4542 {
4543  continue;
4544 }
4545 _ij3[0] = ij3; _ij3[1] = -1;
4546 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
4547 {
4548 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
4549 {
4550  j3valid[iij3]=false; _ij3[1] = iij3; break;
4551 }
4552 }
4553 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
4554 {
4555 IkReal evalcond[6];
4556 IkReal x1038=IKsin(j3);
4557 IkReal x1039=IKcos(j3);
4558 IkReal x1040=((cj7)*(sj8));
4559 IkReal x1041=((r00)*(sj8));
4560 IkReal x1042=((cj8)*(r11));
4561 IkReal x1043=((cj7)*(r02));
4562 IkReal x1044=((cj7)*(r12));
4563 IkReal x1045=((r12)*(sj7));
4564 IkReal x1046=((r02)*(sj7));
4565 IkReal x1047=((sj7)*(sj8));
4566 IkReal x1048=((r10)*(sj8));
4567 IkReal x1049=((cj8)*(r00));
4568 IkReal x1050=((r01)*(x1038));
4569 IkReal x1051=((cj8)*(r10)*(sj7));
4570 IkReal x1052=((IkReal(1.00000000000000))*(x1039));
4571 IkReal x1053=((IkReal(1.00000000000000))*(x1038));
4572 IkReal x1054=((cj7)*(cj8)*(r10));
4573 IkReal x1055=((x1039)*(x1049));
4574 evalcond[0]=((((x1038)*(x1041)))+(((IkReal(-1.00000000000000))*(x1042)*(x1052)))+(((cj8)*(x1050)))+(((IkReal(-1.00000000000000))*(x1048)*(x1052))));
4575 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1052)))+(((IkReal(-1.00000000000000))*(x1042)*(x1053)))+(((IkReal(-1.00000000000000))*(x1041)*(x1052)))+(((cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(x1048)*(x1053)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5))));
4576 evalcond[2]=((((IkReal(-1.00000000000000))*(x1046)*(x1053)))+(((x1039)*(x1054)))+(((x1039)*(x1045)))+(((x1040)*(x1050)))+(((IkReal(-1.00000000000000))*(cj7)*(x1049)*(x1053)))+(((IkReal(-1.00000000000000))*(r11)*(x1040)*(x1052))));
4577 evalcond[3]=((IkReal(-1.00000000000000))+(((x1038)*(x1043)))+(((x1039)*(x1051)))+(((IkReal(-1.00000000000000))*(x1044)*(x1052)))+(((IkReal(-1.00000000000000))*(r11)*(x1047)*(x1052)))+(((IkReal(-1.00000000000000))*(sj7)*(x1049)*(x1053)))+(((x1047)*(x1050))));
4578 evalcond[4]=((((x1038)*(x1045)))+(((x1038)*(x1054)))+(((cj7)*(x1055)))+(((IkReal(-1.00000000000000))*(r01)*(x1040)*(x1052)))+(((x1039)*(x1046)))+(((cj5)*(sj4)))+(((cj4)*(sj5)))+(((IkReal(-1.00000000000000))*(r11)*(x1040)*(x1053))));
4579 evalcond[5]=((((x1038)*(x1051)))+(((IkReal(-1.00000000000000))*(r01)*(x1047)*(x1052)))+(((IkReal(-1.00000000000000))*(x1044)*(x1053)))+(((IkReal(-1.00000000000000))*(x1043)*(x1052)))+(((sj7)*(x1055)))+(((IkReal(-1.00000000000000))*(r11)*(x1047)*(x1053))));
4580 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
4581 {
4582 continue;
4583 }
4584 }
4585 
4586 {
4587 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4588 vinfos[0].jointtype = 1;
4589 vinfos[0].foffset = j3;
4590 vinfos[0].indices[0] = _ij3[0];
4591 vinfos[0].indices[1] = _ij3[1];
4592 vinfos[0].maxsolutions = _nj3;
4593 vinfos[1].jointtype = 1;
4594 vinfos[1].foffset = j4;
4595 vinfos[1].indices[0] = _ij4[0];
4596 vinfos[1].indices[1] = _ij4[1];
4597 vinfos[1].maxsolutions = _nj4;
4598 vinfos[2].jointtype = 1;
4599 vinfos[2].foffset = j5;
4600 vinfos[2].indices[0] = _ij5[0];
4601 vinfos[2].indices[1] = _ij5[1];
4602 vinfos[2].maxsolutions = _nj5;
4603 vinfos[3].jointtype = 1;
4604 vinfos[3].foffset = j6;
4605 vinfos[3].indices[0] = _ij6[0];
4606 vinfos[3].indices[1] = _ij6[1];
4607 vinfos[3].maxsolutions = _nj6;
4608 vinfos[4].jointtype = 1;
4609 vinfos[4].foffset = j7;
4610 vinfos[4].indices[0] = _ij7[0];
4611 vinfos[4].indices[1] = _ij7[1];
4612 vinfos[4].maxsolutions = _nj7;
4613 vinfos[5].jointtype = 1;
4614 vinfos[5].foffset = j8;
4615 vinfos[5].indices[0] = _ij8[0];
4616 vinfos[5].indices[1] = _ij8[1];
4617 vinfos[5].maxsolutions = _nj8;
4618 std::vector<int> vfree(0);
4619 solutions.AddSolution(vinfos,vfree);
4620 }
4621 }
4622 }
4623 
4624 }
4625 
4626 }
4627 
4628 } else
4629 {
4630 {
4631 IkReal j3array[1], cj3array[1], sj3array[1];
4632 bool j3valid[1]={false};
4633 _nj3 = 1;
4634 IkReal x1056=((IkReal(1.00000000000000))*(cj8));
4635 IkReal x1057=((IkReal(1.00000000000000))*(sj8));
4636 if( IKabs(((gconst31)*(((((IkReal(-1.00000000000000))*(r10)*(x1057)))+(((IkReal(-1.00000000000000))*(r11)*(x1056))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst31)*(((((IkReal(-1.00000000000000))*(r00)*(x1057)))+(((IkReal(-1.00000000000000))*(r01)*(x1056))))))) < IKFAST_ATAN2_MAGTHRESH )
4637  continue;
4638 j3array[0]=IKatan2(((gconst31)*(((((IkReal(-1.00000000000000))*(r10)*(x1057)))+(((IkReal(-1.00000000000000))*(r11)*(x1056)))))), ((gconst31)*(((((IkReal(-1.00000000000000))*(r00)*(x1057)))+(((IkReal(-1.00000000000000))*(r01)*(x1056)))))));
4639 sj3array[0]=IKsin(j3array[0]);
4640 cj3array[0]=IKcos(j3array[0]);
4641 if( j3array[0] > IKPI )
4642 {
4643  j3array[0]-=IK2PI;
4644 }
4645 else if( j3array[0] < -IKPI )
4646 { j3array[0]+=IK2PI;
4647 }
4648 j3valid[0] = true;
4649 for(int ij3 = 0; ij3 < 1; ++ij3)
4650 {
4651 if( !j3valid[ij3] )
4652 {
4653  continue;
4654 }
4655 _ij3[0] = ij3; _ij3[1] = -1;
4656 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
4657 {
4658 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
4659 {
4660  j3valid[iij3]=false; _ij3[1] = iij3; break;
4661 }
4662 }
4663 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
4664 {
4665 IkReal evalcond[6];
4666 IkReal x1058=IKsin(j3);
4667 IkReal x1059=IKcos(j3);
4668 IkReal x1060=((cj7)*(sj8));
4669 IkReal x1061=((r00)*(sj8));
4670 IkReal x1062=((cj8)*(r11));
4671 IkReal x1063=((cj7)*(r02));
4672 IkReal x1064=((cj7)*(r12));
4673 IkReal x1065=((r12)*(sj7));
4674 IkReal x1066=((r02)*(sj7));
4675 IkReal x1067=((sj7)*(sj8));
4676 IkReal x1068=((r10)*(sj8));
4677 IkReal x1069=((cj8)*(r00));
4678 IkReal x1070=((r01)*(x1058));
4679 IkReal x1071=((cj8)*(r10)*(sj7));
4680 IkReal x1072=((IkReal(1.00000000000000))*(x1059));
4681 IkReal x1073=((IkReal(1.00000000000000))*(x1058));
4682 IkReal x1074=((cj7)*(cj8)*(r10));
4683 IkReal x1075=((x1059)*(x1069));
4684 evalcond[0]=((((cj8)*(x1070)))+(((IkReal(-1.00000000000000))*(x1062)*(x1072)))+(((IkReal(-1.00000000000000))*(x1068)*(x1072)))+(((x1058)*(x1061))));
4685 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1072)))+(((IkReal(-1.00000000000000))*(x1062)*(x1073)))+(((IkReal(-1.00000000000000))*(x1061)*(x1072)))+(((IkReal(-1.00000000000000))*(x1068)*(x1073)))+(((cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5))));
4686 evalcond[2]=((((x1060)*(x1070)))+(((IkReal(-1.00000000000000))*(r11)*(x1060)*(x1072)))+(((IkReal(-1.00000000000000))*(cj7)*(x1069)*(x1073)))+(((IkReal(-1.00000000000000))*(x1066)*(x1073)))+(((x1059)*(x1065)))+(((x1059)*(x1074))));
4687 evalcond[3]=((IkReal(-1.00000000000000))+(((x1067)*(x1070)))+(((IkReal(-1.00000000000000))*(sj7)*(x1069)*(x1073)))+(((IkReal(-1.00000000000000))*(r11)*(x1067)*(x1072)))+(((IkReal(-1.00000000000000))*(x1064)*(x1072)))+(((x1059)*(x1071)))+(((x1058)*(x1063))));
4688 evalcond[4]=((((x1058)*(x1074)))+(((cj7)*(x1075)))+(((cj5)*(sj4)))+(((IkReal(-1.00000000000000))*(r11)*(x1060)*(x1073)))+(((cj4)*(sj5)))+(((x1059)*(x1066)))+(((IkReal(-1.00000000000000))*(r01)*(x1060)*(x1072)))+(((x1058)*(x1065))));
4689 evalcond[5]=((((IkReal(-1.00000000000000))*(x1063)*(x1072)))+(((x1058)*(x1071)))+(((sj7)*(x1075)))+(((IkReal(-1.00000000000000))*(r11)*(x1067)*(x1073)))+(((IkReal(-1.00000000000000))*(r01)*(x1067)*(x1072)))+(((IkReal(-1.00000000000000))*(x1064)*(x1073))));
4690 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
4691 {
4692 continue;
4693 }
4694 }
4695 
4696 {
4697 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4698 vinfos[0].jointtype = 1;
4699 vinfos[0].foffset = j3;
4700 vinfos[0].indices[0] = _ij3[0];
4701 vinfos[0].indices[1] = _ij3[1];
4702 vinfos[0].maxsolutions = _nj3;
4703 vinfos[1].jointtype = 1;
4704 vinfos[1].foffset = j4;
4705 vinfos[1].indices[0] = _ij4[0];
4706 vinfos[1].indices[1] = _ij4[1];
4707 vinfos[1].maxsolutions = _nj4;
4708 vinfos[2].jointtype = 1;
4709 vinfos[2].foffset = j5;
4710 vinfos[2].indices[0] = _ij5[0];
4711 vinfos[2].indices[1] = _ij5[1];
4712 vinfos[2].maxsolutions = _nj5;
4713 vinfos[3].jointtype = 1;
4714 vinfos[3].foffset = j6;
4715 vinfos[3].indices[0] = _ij6[0];
4716 vinfos[3].indices[1] = _ij6[1];
4717 vinfos[3].maxsolutions = _nj6;
4718 vinfos[4].jointtype = 1;
4719 vinfos[4].foffset = j7;
4720 vinfos[4].indices[0] = _ij7[0];
4721 vinfos[4].indices[1] = _ij7[1];
4722 vinfos[4].maxsolutions = _nj7;
4723 vinfos[5].jointtype = 1;
4724 vinfos[5].foffset = j8;
4725 vinfos[5].indices[0] = _ij8[0];
4726 vinfos[5].indices[1] = _ij8[1];
4727 vinfos[5].maxsolutions = _nj8;
4728 std::vector<int> vfree(0);
4729 solutions.AddSolution(vinfos,vfree);
4730 }
4731 }
4732 }
4733 
4734 }
4735 
4736 }
4737 }
4738 }
4739 
4740 }
4741 
4742 }
4743 
4744 } else
4745 {
4746 IkReal x1076=((IkReal(1.00000000000000))*(sj7));
4747 IkReal x1077=((npy)*(sj8));
4748 IkReal x1078=((cj8)*(npx));
4749 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
4750 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
4751 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
4752 evalcond[3]=((IkReal(0.235000000000000))+(((cj7)*(x1077)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(cj7)*(x1078)))+(((IkReal(-1.00000000000000))*(npz)*(x1076))));
4753 evalcond[4]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x1077)))+(((IkReal(-1.00000000000000))*(x1076)*(x1078)))+(((cj7)*(npz)))+(((IkReal(-0.250000000000000))*(sj5))));
4754 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 )
4755 {
4756 {
4757 IkReal dummyeval[1];
4758 IkReal gconst32;
4759 IkReal x1079=(sj8)*(sj8);
4760 IkReal x1080=(cj8)*(cj8);
4761 IkReal x1081=((IkReal(2.00000000000000))*(cj8)*(sj8));
4762 gconst32=IKsign(((((x1079)*((r10)*(r10))))+(((x1079)*((r00)*(r00))))+(((r10)*(r11)*(x1081)))+(((x1080)*((r11)*(r11))))+(((x1080)*((r01)*(r01))))+(((r00)*(r01)*(x1081)))));
4763 IkReal x1082=(sj8)*(sj8);
4764 IkReal x1083=(cj8)*(cj8);
4765 IkReal x1084=((IkReal(2.00000000000000))*(cj8)*(sj8));
4766 dummyeval[0]=((((x1082)*((r10)*(r10))))+(((x1082)*((r00)*(r00))))+(((x1083)*((r11)*(r11))))+(((r10)*(r11)*(x1084)))+(((r00)*(r01)*(x1084)))+(((x1083)*((r01)*(r01)))));
4767 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4768 {
4769 {
4770 IkReal dummyeval[1];
4771 IkReal gconst34;
4772 gconst34=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
4773 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
4774 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4775 {
4776 {
4777 IkReal dummyeval[1];
4778 IkReal gconst33;
4779 IkReal x1085=(sj8)*(sj8);
4780 IkReal x1086=(cj8)*(cj8);
4781 IkReal x1087=((r00)*(r11));
4782 IkReal x1088=((r02)*(sj7));
4783 IkReal x1089=((cj7)*(x1086));
4784 IkReal x1090=((IkReal(1.00000000000000))*(r12)*(sj7));
4785 IkReal x1091=((IkReal(1.00000000000000))*(r01)*(r10));
4786 IkReal x1092=((cj7)*(x1085));
4787 gconst33=IKsign(((((x1087)*(x1092)))+(((IkReal(-1.00000000000000))*(x1091)*(x1092)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1090)))+(((r10)*(sj8)*(x1088)))+(((IkReal(-1.00000000000000))*(x1089)*(x1091)))+(((x1087)*(x1089)))+(((cj8)*(r11)*(x1088)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1090)))));
4788 IkReal x1093=(sj8)*(sj8);
4789 IkReal x1094=(cj8)*(cj8);
4790 IkReal x1095=((r00)*(r11));
4791 IkReal x1096=((r02)*(sj7));
4792 IkReal x1097=((cj7)*(x1094));
4793 IkReal x1098=((IkReal(1.00000000000000))*(r12)*(sj7));
4794 IkReal x1099=((IkReal(1.00000000000000))*(r01)*(r10));
4795 IkReal x1100=((cj7)*(x1093));
4796 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1098)))+(((cj8)*(r11)*(x1096)))+(((IkReal(-1.00000000000000))*(x1097)*(x1099)))+(((x1095)*(x1097)))+(((IkReal(-1.00000000000000))*(x1099)*(x1100)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1098)))+(((r10)*(sj8)*(x1096)))+(((x1095)*(x1100))));
4797 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4798 {
4799 continue;
4800 
4801 } else
4802 {
4803 {
4804 IkReal j3array[1], cj3array[1], sj3array[1];
4805 bool j3valid[1]={false};
4806 _nj3 = 1;
4807 IkReal x1101=((cj7)*(cj8));
4808 IkReal x1102=((IkReal(1.00000000000000))*(cj7)*(sj8));
4809 if( IKabs(((gconst33)*(((((IkReal(-1.00000000000000))*(r11)*(x1102)))+(((r12)*(sj7)))+(((r10)*(x1101))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst33)*(((((IkReal(-1.00000000000000))*(r01)*(x1102)))+(((r00)*(x1101)))+(((r02)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH )
4810  continue;
4811 j3array[0]=IKatan2(((gconst33)*(((((IkReal(-1.00000000000000))*(r11)*(x1102)))+(((r12)*(sj7)))+(((r10)*(x1101)))))), ((gconst33)*(((((IkReal(-1.00000000000000))*(r01)*(x1102)))+(((r00)*(x1101)))+(((r02)*(sj7)))))));
4812 sj3array[0]=IKsin(j3array[0]);
4813 cj3array[0]=IKcos(j3array[0]);
4814 if( j3array[0] > IKPI )
4815 {
4816  j3array[0]-=IK2PI;
4817 }
4818 else if( j3array[0] < -IKPI )
4819 { j3array[0]+=IK2PI;
4820 }
4821 j3valid[0] = true;
4822 for(int ij3 = 0; ij3 < 1; ++ij3)
4823 {
4824 if( !j3valid[ij3] )
4825 {
4826  continue;
4827 }
4828 _ij3[0] = ij3; _ij3[1] = -1;
4829 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
4830 {
4831 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
4832 {
4833  j3valid[iij3]=false; _ij3[1] = iij3; break;
4834 }
4835 }
4836 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
4837 {
4838 IkReal evalcond[4];
4839 IkReal x1103=IKsin(j3);
4840 IkReal x1104=IKcos(j3);
4841 IkReal x1105=((IkReal(1.00000000000000))*(sj8));
4842 IkReal x1106=((IkReal(1.00000000000000))*(cj8));
4843 IkReal x1107=((r01)*(sj8));
4844 IkReal x1108=((cj8)*(r10));
4845 IkReal x1109=((sj7)*(x1104));
4846 IkReal x1110=((cj7)*(x1103));
4847 IkReal x1111=((r00)*(x1103));
4848 IkReal x1112=((sj7)*(x1103));
4849 IkReal x1113=((cj7)*(x1104));
4850 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x1104)*(x1106)))+(((cj8)*(r01)*(x1103)))+(((IkReal(-1.00000000000000))*(r10)*(x1104)*(x1105)))+(((sj8)*(x1111))));
4851 evalcond[1]=((((IkReal(-1.00000000000000))*(r11)*(x1103)*(x1106)))+(((IkReal(-1.00000000000000))*(r10)*(x1103)*(x1105)))+(((IkReal(-1.00000000000000))*(r01)*(x1104)*(x1106)))+(((IkReal(-1.00000000000000))*(r00)*(x1104)*(x1105))));
4852 evalcond[2]=((((x1108)*(x1113)))+(((IkReal(-1.00000000000000))*(r02)*(x1112)))+(((IkReal(-1.00000000000000))*(r11)*(x1105)*(x1113)))+(((IkReal(-1.00000000000000))*(r00)*(x1106)*(x1110)))+(((r12)*(x1109)))+(((x1107)*(x1110))));
4853 evalcond[3]=((((x1108)*(x1109)))+(((IkReal(-1.00000000000000))*(r11)*(x1105)*(x1109)))+(((IkReal(-1.00000000000000))*(r12)*(x1113)))+(((IkReal(-1.00000000000000))*(sj7)*(x1106)*(x1111)))+(((x1107)*(x1112)))+(((r02)*(x1110))));
4854 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
4855 {
4856 continue;
4857 }
4858 }
4859 
4860 {
4861 IkReal dummyeval[1];
4862 IkReal gconst35;
4863 gconst35=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
4864 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
4865 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4866 {
4867 {
4868 IkReal dummyeval[1];
4869 IkReal gconst36;
4870 gconst36=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
4871 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
4872 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
4873 {
4874 continue;
4875 
4876 } else
4877 {
4878 {
4879 IkReal j4array[1], cj4array[1], sj4array[1];
4880 bool j4valid[1]={false};
4881 _nj4 = 1;
4882 IkReal x1114=((cj3)*(cj5));
4883 IkReal x1115=((r02)*(sj7));
4884 IkReal x1116=((cj5)*(sj7));
4885 IkReal x1117=((cj3)*(sj5));
4886 IkReal x1118=((cj5)*(sj3));
4887 IkReal x1119=((cj7)*(cj8));
4888 IkReal x1120=((IkReal(1.00000000000000))*(sj5));
4889 IkReal x1121=((r12)*(sj3));
4890 IkReal x1122=((sj3)*(sj5));
4891 IkReal x1123=((IkReal(1.00000000000000))*(cj7)*(sj8));
4892 if( IKabs(((gconst36)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((r00)*(x1114)*(x1119)))+(((x1114)*(x1115)))+(((r10)*(x1118)*(x1119)))+(((IkReal(-1.00000000000000))*(r11)*(x1118)*(x1123)))+(((IkReal(-1.00000000000000))*(r20)*(x1119)*(x1120)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1120)))+(((x1116)*(x1121)))+(((IkReal(-1.00000000000000))*(r01)*(x1114)*(x1123))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x1123)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x1120)))+(((sj5)*(sj7)*(x1121)))+(((r22)*(x1116)))+(((r10)*(x1119)*(x1122)))+(((cj5)*(r20)*(x1119)))+(((x1115)*(x1117)))+(((IkReal(-1.00000000000000))*(r01)*(x1117)*(x1123)))+(((r00)*(x1117)*(x1119))))))) < IKFAST_ATAN2_MAGTHRESH )
4893  continue;
4894 j4array[0]=IKatan2(((gconst36)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((r00)*(x1114)*(x1119)))+(((x1114)*(x1115)))+(((r10)*(x1118)*(x1119)))+(((IkReal(-1.00000000000000))*(r11)*(x1118)*(x1123)))+(((IkReal(-1.00000000000000))*(r20)*(x1119)*(x1120)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1120)))+(((x1116)*(x1121)))+(((IkReal(-1.00000000000000))*(r01)*(x1114)*(x1123)))))), ((gconst36)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x1123)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x1120)))+(((sj5)*(sj7)*(x1121)))+(((r22)*(x1116)))+(((r10)*(x1119)*(x1122)))+(((cj5)*(r20)*(x1119)))+(((x1115)*(x1117)))+(((IkReal(-1.00000000000000))*(r01)*(x1117)*(x1123)))+(((r00)*(x1117)*(x1119)))))));
4895 sj4array[0]=IKsin(j4array[0]);
4896 cj4array[0]=IKcos(j4array[0]);
4897 if( j4array[0] > IKPI )
4898 {
4899  j4array[0]-=IK2PI;
4900 }
4901 else if( j4array[0] < -IKPI )
4902 { j4array[0]+=IK2PI;
4903 }
4904 j4valid[0] = true;
4905 for(int ij4 = 0; ij4 < 1; ++ij4)
4906 {
4907 if( !j4valid[ij4] )
4908 {
4909  continue;
4910 }
4911 _ij4[0] = ij4; _ij4[1] = -1;
4912 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
4913 {
4914 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
4915 {
4916  j4valid[iij4]=false; _ij4[1] = iij4; break;
4917 }
4918 }
4919 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
4920 {
4921 IkReal evalcond[4];
4922 IkReal x1124=IKcos(j4);
4923 IkReal x1125=IKsin(j4);
4924 IkReal x1126=((IkReal(1.00000000000000))*(cj7));
4925 IkReal x1127=((cj8)*(r20));
4926 IkReal x1128=((cj3)*(r02));
4927 IkReal x1129=((IkReal(1.00000000000000))*(sj7));
4928 IkReal x1130=((sj3)*(sj7));
4929 IkReal x1131=((r21)*(sj8));
4930 IkReal x1132=((cj8)*(r10));
4931 IkReal x1133=((sj5)*(x1124));
4932 IkReal x1134=((cj5)*(x1125));
4933 IkReal x1135=((r11)*(sj3)*(sj8));
4934 IkReal x1136=((cj3)*(cj8)*(r00));
4935 IkReal x1137=((cj5)*(x1124));
4936 IkReal x1138=((cj3)*(r01)*(sj8));
4937 IkReal x1139=((sj5)*(x1125));
4938 IkReal x1140=((x1133)+(x1134));
4939 evalcond[0]=((x1139)+(((cj7)*(x1131)))+(((IkReal(-1.00000000000000))*(x1126)*(x1127)))+(((IkReal(-1.00000000000000))*(r22)*(x1129)))+(((IkReal(-1.00000000000000))*(x1137))));
4940 evalcond[1]=((x1140)+(((IkReal(-1.00000000000000))*(x1127)*(x1129)))+(((sj7)*(x1131)))+(((cj7)*(r22))));
4941 evalcond[2]=((x1140)+(((cj7)*(x1136)))+(((IkReal(-1.00000000000000))*(x1126)*(x1135)))+(((IkReal(-1.00000000000000))*(x1126)*(x1138)))+(((r12)*(x1130)))+(((sj7)*(x1128)))+(((cj7)*(sj3)*(x1132))));
4942 evalcond[3]=((x1137)+(((x1130)*(x1132)))+(((IkReal(-1.00000000000000))*(x1126)*(x1128)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1126)))+(((IkReal(-1.00000000000000))*(x1139)))+(((sj7)*(x1136)))+(((IkReal(-1.00000000000000))*(x1129)*(x1135)))+(((IkReal(-1.00000000000000))*(x1129)*(x1138))));
4943 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
4944 {
4945 continue;
4946 }
4947 }
4948 
4949 {
4950 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4951 vinfos[0].jointtype = 1;
4952 vinfos[0].foffset = j3;
4953 vinfos[0].indices[0] = _ij3[0];
4954 vinfos[0].indices[1] = _ij3[1];
4955 vinfos[0].maxsolutions = _nj3;
4956 vinfos[1].jointtype = 1;
4957 vinfos[1].foffset = j4;
4958 vinfos[1].indices[0] = _ij4[0];
4959 vinfos[1].indices[1] = _ij4[1];
4960 vinfos[1].maxsolutions = _nj4;
4961 vinfos[2].jointtype = 1;
4962 vinfos[2].foffset = j5;
4963 vinfos[2].indices[0] = _ij5[0];
4964 vinfos[2].indices[1] = _ij5[1];
4965 vinfos[2].maxsolutions = _nj5;
4966 vinfos[3].jointtype = 1;
4967 vinfos[3].foffset = j6;
4968 vinfos[3].indices[0] = _ij6[0];
4969 vinfos[3].indices[1] = _ij6[1];
4970 vinfos[3].maxsolutions = _nj6;
4971 vinfos[4].jointtype = 1;
4972 vinfos[4].foffset = j7;
4973 vinfos[4].indices[0] = _ij7[0];
4974 vinfos[4].indices[1] = _ij7[1];
4975 vinfos[4].maxsolutions = _nj7;
4976 vinfos[5].jointtype = 1;
4977 vinfos[5].foffset = j8;
4978 vinfos[5].indices[0] = _ij8[0];
4979 vinfos[5].indices[1] = _ij8[1];
4980 vinfos[5].maxsolutions = _nj8;
4981 std::vector<int> vfree(0);
4982 solutions.AddSolution(vinfos,vfree);
4983 }
4984 }
4985 }
4986 
4987 }
4988 
4989 }
4990 
4991 } else
4992 {
4993 {
4994 IkReal j4array[1], cj4array[1], sj4array[1];
4995 bool j4valid[1]={false};
4996 _nj4 = 1;
4997 IkReal x1141=((sj5)*(sj7));
4998 IkReal x1142=((r21)*(sj8));
4999 IkReal x1143=((cj5)*(sj7));
5000 IkReal x1144=((cj8)*(r20));
5001 IkReal x1145=((cj5)*(cj7));
5002 IkReal x1146=((cj7)*(sj5));
5003 if( IKabs(((gconst35)*(((((IkReal(-1.00000000000000))*(x1144)*(x1146)))+(((IkReal(-1.00000000000000))*(r22)*(x1141)))+(((r22)*(x1145)))+(((x1142)*(x1146)))+(((x1142)*(x1143)))+(((IkReal(-1.00000000000000))*(x1143)*(x1144))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst35)*(((((r22)*(x1143)))+(((r22)*(x1146)))+(((x1141)*(x1142)))+(((IkReal(-1.00000000000000))*(x1141)*(x1144)))+(((IkReal(-1.00000000000000))*(x1142)*(x1145)))+(((x1144)*(x1145))))))) < IKFAST_ATAN2_MAGTHRESH )
5004  continue;
5005 j4array[0]=IKatan2(((gconst35)*(((((IkReal(-1.00000000000000))*(x1144)*(x1146)))+(((IkReal(-1.00000000000000))*(r22)*(x1141)))+(((r22)*(x1145)))+(((x1142)*(x1146)))+(((x1142)*(x1143)))+(((IkReal(-1.00000000000000))*(x1143)*(x1144)))))), ((gconst35)*(((((r22)*(x1143)))+(((r22)*(x1146)))+(((x1141)*(x1142)))+(((IkReal(-1.00000000000000))*(x1141)*(x1144)))+(((IkReal(-1.00000000000000))*(x1142)*(x1145)))+(((x1144)*(x1145)))))));
5006 sj4array[0]=IKsin(j4array[0]);
5007 cj4array[0]=IKcos(j4array[0]);
5008 if( j4array[0] > IKPI )
5009 {
5010  j4array[0]-=IK2PI;
5011 }
5012 else if( j4array[0] < -IKPI )
5013 { j4array[0]+=IK2PI;
5014 }
5015 j4valid[0] = true;
5016 for(int ij4 = 0; ij4 < 1; ++ij4)
5017 {
5018 if( !j4valid[ij4] )
5019 {
5020  continue;
5021 }
5022 _ij4[0] = ij4; _ij4[1] = -1;
5023 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
5024 {
5025 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
5026 {
5027  j4valid[iij4]=false; _ij4[1] = iij4; break;
5028 }
5029 }
5030 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
5031 {
5032 IkReal evalcond[4];
5033 IkReal x1147=IKcos(j4);
5034 IkReal x1148=IKsin(j4);
5035 IkReal x1149=((IkReal(1.00000000000000))*(cj7));
5036 IkReal x1150=((cj8)*(r20));
5037 IkReal x1151=((cj3)*(r02));
5038 IkReal x1152=((IkReal(1.00000000000000))*(sj7));
5039 IkReal x1153=((sj3)*(sj7));
5040 IkReal x1154=((r21)*(sj8));
5041 IkReal x1155=((cj8)*(r10));
5042 IkReal x1156=((sj5)*(x1147));
5043 IkReal x1157=((cj5)*(x1148));
5044 IkReal x1158=((r11)*(sj3)*(sj8));
5045 IkReal x1159=((cj3)*(cj8)*(r00));
5046 IkReal x1160=((cj5)*(x1147));
5047 IkReal x1161=((cj3)*(r01)*(sj8));
5048 IkReal x1162=((sj5)*(x1148));
5049 IkReal x1163=((x1157)+(x1156));
5050 evalcond[0]=((x1162)+(((IkReal(-1.00000000000000))*(x1149)*(x1150)))+(((IkReal(-1.00000000000000))*(r22)*(x1152)))+(((cj7)*(x1154)))+(((IkReal(-1.00000000000000))*(x1160))));
5051 evalcond[1]=((x1163)+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x1150)*(x1152)))+(((sj7)*(x1154))));
5052 evalcond[2]=((x1163)+(((IkReal(-1.00000000000000))*(x1149)*(x1158)))+(((r12)*(x1153)))+(((IkReal(-1.00000000000000))*(x1149)*(x1161)))+(((cj7)*(sj3)*(x1155)))+(((cj7)*(x1159)))+(((sj7)*(x1151))));
5053 evalcond[3]=((x1160)+(((IkReal(-1.00000000000000))*(x1149)*(x1151)))+(((IkReal(-1.00000000000000))*(x1152)*(x1161)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1149)))+(((x1153)*(x1155)))+(((IkReal(-1.00000000000000))*(x1152)*(x1158)))+(((IkReal(-1.00000000000000))*(x1162)))+(((sj7)*(x1159))));
5054 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
5055 {
5056 continue;
5057 }
5058 }
5059 
5060 {
5061 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5062 vinfos[0].jointtype = 1;
5063 vinfos[0].foffset = j3;
5064 vinfos[0].indices[0] = _ij3[0];
5065 vinfos[0].indices[1] = _ij3[1];
5066 vinfos[0].maxsolutions = _nj3;
5067 vinfos[1].jointtype = 1;
5068 vinfos[1].foffset = j4;
5069 vinfos[1].indices[0] = _ij4[0];
5070 vinfos[1].indices[1] = _ij4[1];
5071 vinfos[1].maxsolutions = _nj4;
5072 vinfos[2].jointtype = 1;
5073 vinfos[2].foffset = j5;
5074 vinfos[2].indices[0] = _ij5[0];
5075 vinfos[2].indices[1] = _ij5[1];
5076 vinfos[2].maxsolutions = _nj5;
5077 vinfos[3].jointtype = 1;
5078 vinfos[3].foffset = j6;
5079 vinfos[3].indices[0] = _ij6[0];
5080 vinfos[3].indices[1] = _ij6[1];
5081 vinfos[3].maxsolutions = _nj6;
5082 vinfos[4].jointtype = 1;
5083 vinfos[4].foffset = j7;
5084 vinfos[4].indices[0] = _ij7[0];
5085 vinfos[4].indices[1] = _ij7[1];
5086 vinfos[4].maxsolutions = _nj7;
5087 vinfos[5].jointtype = 1;
5088 vinfos[5].foffset = j8;
5089 vinfos[5].indices[0] = _ij8[0];
5090 vinfos[5].indices[1] = _ij8[1];
5091 vinfos[5].maxsolutions = _nj8;
5092 std::vector<int> vfree(0);
5093 solutions.AddSolution(vinfos,vfree);
5094 }
5095 }
5096 }
5097 
5098 }
5099 
5100 }
5101 }
5102 }
5103 
5104 }
5105 
5106 }
5107 
5108 } else
5109 {
5110 {
5111 IkReal j4array[1], cj4array[1], sj4array[1];
5112 bool j4valid[1]={false};
5113 _nj4 = 1;
5114 IkReal x1164=((sj5)*(sj7));
5115 IkReal x1165=((r21)*(sj8));
5116 IkReal x1166=((cj5)*(sj7));
5117 IkReal x1167=((cj7)*(sj5));
5118 IkReal x1168=((cj5)*(cj7));
5119 IkReal x1169=((IkReal(1.00000000000000))*(cj8)*(r20));
5120 if( IKabs(((gconst34)*(((((IkReal(-1.00000000000000))*(x1166)*(x1169)))+(((x1165)*(x1166)))+(((x1165)*(x1167)))+(((IkReal(-1.00000000000000))*(x1167)*(x1169)))+(((IkReal(-1.00000000000000))*(r22)*(x1164)))+(((r22)*(x1168))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst34)*(((((x1164)*(x1165)))+(((IkReal(-1.00000000000000))*(x1165)*(x1168)))+(((cj8)*(r20)*(x1168)))+(((r22)*(x1166)))+(((r22)*(x1167)))+(((IkReal(-1.00000000000000))*(x1164)*(x1169))))))) < IKFAST_ATAN2_MAGTHRESH )
5121  continue;
5122 j4array[0]=IKatan2(((gconst34)*(((((IkReal(-1.00000000000000))*(x1166)*(x1169)))+(((x1165)*(x1166)))+(((x1165)*(x1167)))+(((IkReal(-1.00000000000000))*(x1167)*(x1169)))+(((IkReal(-1.00000000000000))*(r22)*(x1164)))+(((r22)*(x1168)))))), ((gconst34)*(((((x1164)*(x1165)))+(((IkReal(-1.00000000000000))*(x1165)*(x1168)))+(((cj8)*(r20)*(x1168)))+(((r22)*(x1166)))+(((r22)*(x1167)))+(((IkReal(-1.00000000000000))*(x1164)*(x1169)))))));
5123 sj4array[0]=IKsin(j4array[0]);
5124 cj4array[0]=IKcos(j4array[0]);
5125 if( j4array[0] > IKPI )
5126 {
5127  j4array[0]-=IK2PI;
5128 }
5129 else if( j4array[0] < -IKPI )
5130 { j4array[0]+=IK2PI;
5131 }
5132 j4valid[0] = true;
5133 for(int ij4 = 0; ij4 < 1; ++ij4)
5134 {
5135 if( !j4valid[ij4] )
5136 {
5137  continue;
5138 }
5139 _ij4[0] = ij4; _ij4[1] = -1;
5140 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
5141 {
5142 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
5143 {
5144  j4valid[iij4]=false; _ij4[1] = iij4; break;
5145 }
5146 }
5147 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
5148 {
5149 IkReal evalcond[2];
5150 IkReal x1170=IKcos(j4);
5151 IkReal x1171=IKsin(j4);
5152 IkReal x1172=((r21)*(sj8));
5153 IkReal x1173=((IkReal(1.00000000000000))*(cj8)*(r20));
5154 evalcond[0]=((((IkReal(-1.00000000000000))*(cj7)*(x1173)))+(((cj7)*(x1172)))+(((IkReal(-1.00000000000000))*(cj5)*(x1170)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((sj5)*(x1171))));
5155 evalcond[1]=((((cj5)*(x1171)))+(((sj7)*(x1172)))+(((sj5)*(x1170)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(sj7)*(x1173))));
5156 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
5157 {
5158 continue;
5159 }
5160 }
5161 
5162 {
5163 IkReal dummyeval[1];
5164 IkReal gconst37;
5165 IkReal x1174=(sj8)*(sj8);
5166 IkReal x1175=(cj8)*(cj8);
5167 IkReal x1176=((IkReal(2.00000000000000))*(cj8)*(sj8));
5168 gconst37=IKsign(((((x1175)*((r11)*(r11))))+(((r10)*(r11)*(x1176)))+(((x1174)*((r00)*(r00))))+(((r00)*(r01)*(x1176)))+(((x1174)*((r10)*(r10))))+(((x1175)*((r01)*(r01))))));
5169 IkReal x1177=(sj8)*(sj8);
5170 IkReal x1178=(cj8)*(cj8);
5171 IkReal x1179=((IkReal(2.00000000000000))*(cj8)*(sj8));
5172 dummyeval[0]=((((x1178)*((r11)*(r11))))+(((r10)*(r11)*(x1179)))+(((r00)*(r01)*(x1179)))+(((x1177)*((r10)*(r10))))+(((x1178)*((r01)*(r01))))+(((x1177)*((r00)*(r00)))));
5173 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5174 {
5175 {
5176 IkReal dummyeval[1];
5177 IkReal gconst38;
5178 IkReal x1180=(sj8)*(sj8);
5179 IkReal x1181=(cj8)*(cj8);
5180 IkReal x1182=((r00)*(r11));
5181 IkReal x1183=((r02)*(sj7));
5182 IkReal x1184=((cj7)*(x1181));
5183 IkReal x1185=((IkReal(1.00000000000000))*(r12)*(sj7));
5184 IkReal x1186=((IkReal(1.00000000000000))*(r01)*(r10));
5185 IkReal x1187=((cj7)*(x1180));
5186 gconst38=IKsign(((((r10)*(sj8)*(x1183)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1185)))+(((cj8)*(r11)*(x1183)))+(((x1182)*(x1184)))+(((x1182)*(x1187)))+(((IkReal(-1.00000000000000))*(x1186)*(x1187)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1185)))+(((IkReal(-1.00000000000000))*(x1184)*(x1186)))));
5187 IkReal x1188=(sj8)*(sj8);
5188 IkReal x1189=(cj8)*(cj8);
5189 IkReal x1190=((r00)*(r11));
5190 IkReal x1191=((r02)*(sj7));
5191 IkReal x1192=((cj7)*(x1189));
5192 IkReal x1193=((IkReal(1.00000000000000))*(r12)*(sj7));
5193 IkReal x1194=((IkReal(1.00000000000000))*(r01)*(r10));
5194 IkReal x1195=((cj7)*(x1188));
5195 dummyeval[0]=((((r10)*(sj8)*(x1191)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1193)))+(((cj8)*(r11)*(x1191)))+(((IkReal(-1.00000000000000))*(x1194)*(x1195)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1193)))+(((IkReal(-1.00000000000000))*(x1192)*(x1194)))+(((x1190)*(x1195)))+(((x1190)*(x1192))));
5196 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5197 {
5198 continue;
5199 
5200 } else
5201 {
5202 {
5203 IkReal j3array[1], cj3array[1], sj3array[1];
5204 bool j3valid[1]={false};
5205 _nj3 = 1;
5206 IkReal x1196=((cj7)*(cj8));
5207 IkReal x1197=((IkReal(1.00000000000000))*(cj7)*(sj8));
5208 if( IKabs(((gconst38)*(((((r10)*(x1196)))+(((r12)*(sj7)))+(((IkReal(-1.00000000000000))*(r11)*(x1197))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((r00)*(x1196)))+(((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x1197))))))) < IKFAST_ATAN2_MAGTHRESH )
5209  continue;
5210 j3array[0]=IKatan2(((gconst38)*(((((r10)*(x1196)))+(((r12)*(sj7)))+(((IkReal(-1.00000000000000))*(r11)*(x1197)))))), ((gconst38)*(((((r00)*(x1196)))+(((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x1197)))))));
5211 sj3array[0]=IKsin(j3array[0]);
5212 cj3array[0]=IKcos(j3array[0]);
5213 if( j3array[0] > IKPI )
5214 {
5215  j3array[0]-=IK2PI;
5216 }
5217 else if( j3array[0] < -IKPI )
5218 { j3array[0]+=IK2PI;
5219 }
5220 j3valid[0] = true;
5221 for(int ij3 = 0; ij3 < 1; ++ij3)
5222 {
5223 if( !j3valid[ij3] )
5224 {
5225  continue;
5226 }
5227 _ij3[0] = ij3; _ij3[1] = -1;
5228 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
5229 {
5230 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5231 {
5232  j3valid[iij3]=false; _ij3[1] = iij3; break;
5233 }
5234 }
5235 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5236 {
5237 IkReal evalcond[6];
5238 IkReal x1198=IKsin(j3);
5239 IkReal x1199=IKcos(j3);
5240 IkReal x1200=((r01)*(sj8));
5241 IkReal x1201=((cj8)*(r00));
5242 IkReal x1202=((r00)*(sj8));
5243 IkReal x1203=((cj8)*(r11));
5244 IkReal x1204=((r11)*(sj8));
5245 IkReal x1205=((r10)*(sj8));
5246 IkReal x1206=((cj8)*(r10));
5247 IkReal x1207=((cj7)*(x1198));
5248 IkReal x1208=((sj7)*(x1199));
5249 IkReal x1209=((IkReal(1.00000000000000))*(x1198));
5250 IkReal x1210=((IkReal(1.00000000000000))*(x1199));
5251 IkReal x1211=((cj8)*(x1198));
5252 IkReal x1212=((IkReal(1.00000000000000))*(x1204));
5253 IkReal x1213=((sj7)*(x1198));
5254 IkReal x1214=((cj7)*(x1199));
5255 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1203)*(x1210)))+(((r01)*(x1211)))+(((IkReal(-1.00000000000000))*(x1205)*(x1210)))+(((x1198)*(x1202))));
5256 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1210)))+(((IkReal(-1.00000000000000))*(x1202)*(x1210)))+(((IkReal(-1.00000000000000))*(x1205)*(x1209)))+(((IkReal(-1.00000000000000))*(x1203)*(x1209))));
5257 evalcond[2]=((((IkReal(-1.00000000000000))*(cj7)*(x1204)*(x1210)))+(((r12)*(x1208)))+(((x1206)*(x1214)))+(((x1200)*(x1207)))+(((IkReal(-1.00000000000000))*(x1201)*(x1207)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1209))));
5258 evalcond[3]=((((IkReal(-1.00000000000000))*(x1208)*(x1212)))+(((x1200)*(x1213)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1210)))+(((x1206)*(x1208)))+(((r02)*(x1207)))+(((IkReal(-1.00000000000000))*(sj7)*(x1201)*(x1209))));
5259 evalcond[4]=((((r12)*(x1213)))+(((IkReal(-1.00000000000000))*(x1207)*(x1212)))+(((cj5)*(sj4)))+(((cj4)*(sj5)))+(((IkReal(-1.00000000000000))*(cj7)*(x1200)*(x1210)))+(((x1201)*(x1214)))+(((x1206)*(x1207)))+(((r02)*(x1208))));
5260 evalcond[5]=((((IkReal(-1.00000000000000))*(x1200)*(x1208)))+(((x1206)*(x1213)))+(((cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(sj7)*(x1204)*(x1209)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1210)))+(((x1201)*(x1208)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(r12)*(x1207))));
5261 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
5262 {
5263 continue;
5264 }
5265 }
5266 
5267 {
5268 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5269 vinfos[0].jointtype = 1;
5270 vinfos[0].foffset = j3;
5271 vinfos[0].indices[0] = _ij3[0];
5272 vinfos[0].indices[1] = _ij3[1];
5273 vinfos[0].maxsolutions = _nj3;
5274 vinfos[1].jointtype = 1;
5275 vinfos[1].foffset = j4;
5276 vinfos[1].indices[0] = _ij4[0];
5277 vinfos[1].indices[1] = _ij4[1];
5278 vinfos[1].maxsolutions = _nj4;
5279 vinfos[2].jointtype = 1;
5280 vinfos[2].foffset = j5;
5281 vinfos[2].indices[0] = _ij5[0];
5282 vinfos[2].indices[1] = _ij5[1];
5283 vinfos[2].maxsolutions = _nj5;
5284 vinfos[3].jointtype = 1;
5285 vinfos[3].foffset = j6;
5286 vinfos[3].indices[0] = _ij6[0];
5287 vinfos[3].indices[1] = _ij6[1];
5288 vinfos[3].maxsolutions = _nj6;
5289 vinfos[4].jointtype = 1;
5290 vinfos[4].foffset = j7;
5291 vinfos[4].indices[0] = _ij7[0];
5292 vinfos[4].indices[1] = _ij7[1];
5293 vinfos[4].maxsolutions = _nj7;
5294 vinfos[5].jointtype = 1;
5295 vinfos[5].foffset = j8;
5296 vinfos[5].indices[0] = _ij8[0];
5297 vinfos[5].indices[1] = _ij8[1];
5298 vinfos[5].maxsolutions = _nj8;
5299 std::vector<int> vfree(0);
5300 solutions.AddSolution(vinfos,vfree);
5301 }
5302 }
5303 }
5304 
5305 }
5306 
5307 }
5308 
5309 } else
5310 {
5311 {
5312 IkReal j3array[1], cj3array[1], sj3array[1];
5313 bool j3valid[1]={false};
5314 _nj3 = 1;
5315 if( IKabs(((gconst37)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
5316  continue;
5317 j3array[0]=IKatan2(((gconst37)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst37)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
5318 sj3array[0]=IKsin(j3array[0]);
5319 cj3array[0]=IKcos(j3array[0]);
5320 if( j3array[0] > IKPI )
5321 {
5322  j3array[0]-=IK2PI;
5323 }
5324 else if( j3array[0] < -IKPI )
5325 { j3array[0]+=IK2PI;
5326 }
5327 j3valid[0] = true;
5328 for(int ij3 = 0; ij3 < 1; ++ij3)
5329 {
5330 if( !j3valid[ij3] )
5331 {
5332  continue;
5333 }
5334 _ij3[0] = ij3; _ij3[1] = -1;
5335 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
5336 {
5337 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5338 {
5339  j3valid[iij3]=false; _ij3[1] = iij3; break;
5340 }
5341 }
5342 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5343 {
5344 IkReal evalcond[6];
5345 IkReal x1215=IKsin(j3);
5346 IkReal x1216=IKcos(j3);
5347 IkReal x1217=((r01)*(sj8));
5348 IkReal x1218=((cj8)*(r00));
5349 IkReal x1219=((r00)*(sj8));
5350 IkReal x1220=((cj8)*(r11));
5351 IkReal x1221=((r11)*(sj8));
5352 IkReal x1222=((r10)*(sj8));
5353 IkReal x1223=((cj8)*(r10));
5354 IkReal x1224=((cj7)*(x1215));
5355 IkReal x1225=((sj7)*(x1216));
5356 IkReal x1226=((IkReal(1.00000000000000))*(x1215));
5357 IkReal x1227=((IkReal(1.00000000000000))*(x1216));
5358 IkReal x1228=((cj8)*(x1215));
5359 IkReal x1229=((IkReal(1.00000000000000))*(x1221));
5360 IkReal x1230=((sj7)*(x1215));
5361 IkReal x1231=((cj7)*(x1216));
5362 evalcond[0]=((IkReal(1.00000000000000))+(((r01)*(x1228)))+(((IkReal(-1.00000000000000))*(x1220)*(x1227)))+(((IkReal(-1.00000000000000))*(x1222)*(x1227)))+(((x1215)*(x1219))));
5363 evalcond[1]=((((IkReal(-1.00000000000000))*(x1220)*(x1226)))+(((IkReal(-1.00000000000000))*(x1222)*(x1226)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1227)))+(((IkReal(-1.00000000000000))*(x1219)*(x1227))));
5364 evalcond[2]=((((IkReal(-1.00000000000000))*(x1218)*(x1224)))+(((x1217)*(x1224)))+(((x1223)*(x1231)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1226)))+(((IkReal(-1.00000000000000))*(cj7)*(x1221)*(x1227)))+(((r12)*(x1225))));
5365 evalcond[3]=((((x1217)*(x1230)))+(((IkReal(-1.00000000000000))*(x1225)*(x1229)))+(((x1223)*(x1225)))+(((r02)*(x1224)))+(((IkReal(-1.00000000000000))*(sj7)*(x1218)*(x1226)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1227))));
5366 evalcond[4]=((((IkReal(-1.00000000000000))*(cj7)*(x1217)*(x1227)))+(((IkReal(-1.00000000000000))*(x1224)*(x1229)))+(((x1223)*(x1224)))+(((cj5)*(sj4)))+(((r02)*(x1225)))+(((cj4)*(sj5)))+(((x1218)*(x1231)))+(((r12)*(x1230))));
5367 evalcond[5]=((((IkReal(-1.00000000000000))*(sj7)*(x1221)*(x1226)))+(((IkReal(-1.00000000000000))*(x1217)*(x1225)))+(((x1223)*(x1230)))+(((IkReal(-1.00000000000000))*(r12)*(x1224)))+(((cj4)*(cj5)))+(((x1218)*(x1225)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1227)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5))));
5368 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
5369 {
5370 continue;
5371 }
5372 }
5373 
5374 {
5375 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5376 vinfos[0].jointtype = 1;
5377 vinfos[0].foffset = j3;
5378 vinfos[0].indices[0] = _ij3[0];
5379 vinfos[0].indices[1] = _ij3[1];
5380 vinfos[0].maxsolutions = _nj3;
5381 vinfos[1].jointtype = 1;
5382 vinfos[1].foffset = j4;
5383 vinfos[1].indices[0] = _ij4[0];
5384 vinfos[1].indices[1] = _ij4[1];
5385 vinfos[1].maxsolutions = _nj4;
5386 vinfos[2].jointtype = 1;
5387 vinfos[2].foffset = j5;
5388 vinfos[2].indices[0] = _ij5[0];
5389 vinfos[2].indices[1] = _ij5[1];
5390 vinfos[2].maxsolutions = _nj5;
5391 vinfos[3].jointtype = 1;
5392 vinfos[3].foffset = j6;
5393 vinfos[3].indices[0] = _ij6[0];
5394 vinfos[3].indices[1] = _ij6[1];
5395 vinfos[3].maxsolutions = _nj6;
5396 vinfos[4].jointtype = 1;
5397 vinfos[4].foffset = j7;
5398 vinfos[4].indices[0] = _ij7[0];
5399 vinfos[4].indices[1] = _ij7[1];
5400 vinfos[4].maxsolutions = _nj7;
5401 vinfos[5].jointtype = 1;
5402 vinfos[5].foffset = j8;
5403 vinfos[5].indices[0] = _ij8[0];
5404 vinfos[5].indices[1] = _ij8[1];
5405 vinfos[5].maxsolutions = _nj8;
5406 std::vector<int> vfree(0);
5407 solutions.AddSolution(vinfos,vfree);
5408 }
5409 }
5410 }
5411 
5412 }
5413 
5414 }
5415 }
5416 }
5417 
5418 }
5419 
5420 }
5421 
5422 } else
5423 {
5424 {
5425 IkReal j3array[1], cj3array[1], sj3array[1];
5426 bool j3valid[1]={false};
5427 _nj3 = 1;
5428 if( IKabs(((gconst32)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst32)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
5429  continue;
5430 j3array[0]=IKatan2(((gconst32)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst32)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
5431 sj3array[0]=IKsin(j3array[0]);
5432 cj3array[0]=IKcos(j3array[0]);
5433 if( j3array[0] > IKPI )
5434 {
5435  j3array[0]-=IK2PI;
5436 }
5437 else if( j3array[0] < -IKPI )
5438 { j3array[0]+=IK2PI;
5439 }
5440 j3valid[0] = true;
5441 for(int ij3 = 0; ij3 < 1; ++ij3)
5442 {
5443 if( !j3valid[ij3] )
5444 {
5445  continue;
5446 }
5447 _ij3[0] = ij3; _ij3[1] = -1;
5448 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
5449 {
5450 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5451 {
5452  j3valid[iij3]=false; _ij3[1] = iij3; break;
5453 }
5454 }
5455 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5456 {
5457 IkReal evalcond[4];
5458 IkReal x1232=IKsin(j3);
5459 IkReal x1233=IKcos(j3);
5460 IkReal x1234=((IkReal(1.00000000000000))*(sj8));
5461 IkReal x1235=((IkReal(1.00000000000000))*(cj8));
5462 IkReal x1236=((r01)*(sj8));
5463 IkReal x1237=((cj8)*(r10));
5464 IkReal x1238=((sj7)*(x1233));
5465 IkReal x1239=((cj7)*(x1232));
5466 IkReal x1240=((r00)*(x1232));
5467 IkReal x1241=((sj7)*(x1232));
5468 IkReal x1242=((cj7)*(x1233));
5469 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x1233)*(x1235)))+(((cj8)*(r01)*(x1232)))+(((IkReal(-1.00000000000000))*(r10)*(x1233)*(x1234)))+(((sj8)*(x1240))));
5470 evalcond[1]=((((IkReal(-1.00000000000000))*(r11)*(x1232)*(x1235)))+(((IkReal(-1.00000000000000))*(r00)*(x1233)*(x1234)))+(((IkReal(-1.00000000000000))*(r01)*(x1233)*(x1235)))+(((IkReal(-1.00000000000000))*(r10)*(x1232)*(x1234))));
5471 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x1235)*(x1239)))+(((IkReal(-1.00000000000000))*(r11)*(x1234)*(x1242)))+(((IkReal(-1.00000000000000))*(r02)*(x1241)))+(((x1236)*(x1239)))+(((x1237)*(x1242)))+(((r12)*(x1238))));
5472 evalcond[3]=((((x1236)*(x1241)))+(((IkReal(-1.00000000000000))*(r12)*(x1242)))+(((IkReal(-1.00000000000000))*(r11)*(x1234)*(x1238)))+(((r02)*(x1239)))+(((IkReal(-1.00000000000000))*(sj7)*(x1235)*(x1240)))+(((x1237)*(x1238))));
5473 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
5474 {
5475 continue;
5476 }
5477 }
5478 
5479 {
5480 IkReal dummyeval[1];
5481 IkReal gconst35;
5482 gconst35=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
5483 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
5484 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5485 {
5486 {
5487 IkReal dummyeval[1];
5488 IkReal gconst36;
5489 gconst36=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
5490 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
5491 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5492 {
5493 continue;
5494 
5495 } else
5496 {
5497 {
5498 IkReal j4array[1], cj4array[1], sj4array[1];
5499 bool j4valid[1]={false};
5500 _nj4 = 1;
5501 IkReal x1243=((cj3)*(cj5));
5502 IkReal x1244=((r02)*(sj7));
5503 IkReal x1245=((cj5)*(sj7));
5504 IkReal x1246=((cj3)*(sj5));
5505 IkReal x1247=((cj5)*(sj3));
5506 IkReal x1248=((cj7)*(cj8));
5507 IkReal x1249=((IkReal(1.00000000000000))*(sj5));
5508 IkReal x1250=((r12)*(sj3));
5509 IkReal x1251=((sj3)*(sj5));
5510 IkReal x1252=((IkReal(1.00000000000000))*(cj7)*(sj8));
5511 if( IKabs(((gconst36)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x1248)*(x1249)))+(((x1245)*(x1250)))+(((r00)*(x1243)*(x1248)))+(((IkReal(-1.00000000000000))*(r11)*(x1247)*(x1252)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1249)))+(((x1243)*(x1244)))+(((IkReal(-1.00000000000000))*(r01)*(x1243)*(x1252)))+(((r10)*(x1247)*(x1248))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x1249)))+(((cj5)*(r20)*(x1248)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x1252)))+(((r10)*(x1248)*(x1251)))+(((IkReal(-1.00000000000000))*(r01)*(x1246)*(x1252)))+(((r00)*(x1246)*(x1248)))+(((sj5)*(sj7)*(x1250)))+(((x1244)*(x1246)))+(((r22)*(x1245))))))) < IKFAST_ATAN2_MAGTHRESH )
5512  continue;
5513 j4array[0]=IKatan2(((gconst36)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x1248)*(x1249)))+(((x1245)*(x1250)))+(((r00)*(x1243)*(x1248)))+(((IkReal(-1.00000000000000))*(r11)*(x1247)*(x1252)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1249)))+(((x1243)*(x1244)))+(((IkReal(-1.00000000000000))*(r01)*(x1243)*(x1252)))+(((r10)*(x1247)*(x1248)))))), ((gconst36)*(((((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x1249)))+(((cj5)*(r20)*(x1248)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x1252)))+(((r10)*(x1248)*(x1251)))+(((IkReal(-1.00000000000000))*(r01)*(x1246)*(x1252)))+(((r00)*(x1246)*(x1248)))+(((sj5)*(sj7)*(x1250)))+(((x1244)*(x1246)))+(((r22)*(x1245)))))));
5514 sj4array[0]=IKsin(j4array[0]);
5515 cj4array[0]=IKcos(j4array[0]);
5516 if( j4array[0] > IKPI )
5517 {
5518  j4array[0]-=IK2PI;
5519 }
5520 else if( j4array[0] < -IKPI )
5521 { j4array[0]+=IK2PI;
5522 }
5523 j4valid[0] = true;
5524 for(int ij4 = 0; ij4 < 1; ++ij4)
5525 {
5526 if( !j4valid[ij4] )
5527 {
5528  continue;
5529 }
5530 _ij4[0] = ij4; _ij4[1] = -1;
5531 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
5532 {
5533 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
5534 {
5535  j4valid[iij4]=false; _ij4[1] = iij4; break;
5536 }
5537 }
5538 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
5539 {
5540 IkReal evalcond[4];
5541 IkReal x1253=IKcos(j4);
5542 IkReal x1254=IKsin(j4);
5543 IkReal x1255=((IkReal(1.00000000000000))*(cj7));
5544 IkReal x1256=((cj8)*(r20));
5545 IkReal x1257=((cj3)*(r02));
5546 IkReal x1258=((IkReal(1.00000000000000))*(sj7));
5547 IkReal x1259=((sj3)*(sj7));
5548 IkReal x1260=((r21)*(sj8));
5549 IkReal x1261=((cj8)*(r10));
5550 IkReal x1262=((sj5)*(x1253));
5551 IkReal x1263=((cj5)*(x1254));
5552 IkReal x1264=((r11)*(sj3)*(sj8));
5553 IkReal x1265=((cj3)*(cj8)*(r00));
5554 IkReal x1266=((cj5)*(x1253));
5555 IkReal x1267=((cj3)*(r01)*(sj8));
5556 IkReal x1268=((sj5)*(x1254));
5557 IkReal x1269=((x1263)+(x1262));
5558 evalcond[0]=((x1268)+(((cj7)*(x1260)))+(((IkReal(-1.00000000000000))*(r22)*(x1258)))+(((IkReal(-1.00000000000000))*(x1255)*(x1256)))+(((IkReal(-1.00000000000000))*(x1266))));
5559 evalcond[1]=((x1269)+(((sj7)*(x1260)))+(((IkReal(-1.00000000000000))*(x1256)*(x1258)))+(((cj7)*(r22))));
5560 evalcond[2]=((x1269)+(((cj7)*(x1265)))+(((r12)*(x1259)))+(((sj7)*(x1257)))+(((IkReal(-1.00000000000000))*(x1255)*(x1267)))+(((IkReal(-1.00000000000000))*(x1255)*(x1264)))+(((cj7)*(sj3)*(x1261))));
5561 evalcond[3]=((((IkReal(-1.00000000000000))*(x1258)*(x1267)))+(((IkReal(-1.00000000000000))*(x1258)*(x1264)))+(x1266)+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1255)))+(((sj7)*(x1265)))+(((IkReal(-1.00000000000000))*(x1255)*(x1257)))+(((x1259)*(x1261)))+(((IkReal(-1.00000000000000))*(x1268))));
5562 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
5563 {
5564 continue;
5565 }
5566 }
5567 
5568 {
5569 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5570 vinfos[0].jointtype = 1;
5571 vinfos[0].foffset = j3;
5572 vinfos[0].indices[0] = _ij3[0];
5573 vinfos[0].indices[1] = _ij3[1];
5574 vinfos[0].maxsolutions = _nj3;
5575 vinfos[1].jointtype = 1;
5576 vinfos[1].foffset = j4;
5577 vinfos[1].indices[0] = _ij4[0];
5578 vinfos[1].indices[1] = _ij4[1];
5579 vinfos[1].maxsolutions = _nj4;
5580 vinfos[2].jointtype = 1;
5581 vinfos[2].foffset = j5;
5582 vinfos[2].indices[0] = _ij5[0];
5583 vinfos[2].indices[1] = _ij5[1];
5584 vinfos[2].maxsolutions = _nj5;
5585 vinfos[3].jointtype = 1;
5586 vinfos[3].foffset = j6;
5587 vinfos[3].indices[0] = _ij6[0];
5588 vinfos[3].indices[1] = _ij6[1];
5589 vinfos[3].maxsolutions = _nj6;
5590 vinfos[4].jointtype = 1;
5591 vinfos[4].foffset = j7;
5592 vinfos[4].indices[0] = _ij7[0];
5593 vinfos[4].indices[1] = _ij7[1];
5594 vinfos[4].maxsolutions = _nj7;
5595 vinfos[5].jointtype = 1;
5596 vinfos[5].foffset = j8;
5597 vinfos[5].indices[0] = _ij8[0];
5598 vinfos[5].indices[1] = _ij8[1];
5599 vinfos[5].maxsolutions = _nj8;
5600 std::vector<int> vfree(0);
5601 solutions.AddSolution(vinfos,vfree);
5602 }
5603 }
5604 }
5605 
5606 }
5607 
5608 }
5609 
5610 } else
5611 {
5612 {
5613 IkReal j4array[1], cj4array[1], sj4array[1];
5614 bool j4valid[1]={false};
5615 _nj4 = 1;
5616 IkReal x1270=((sj5)*(sj7));
5617 IkReal x1271=((r21)*(sj8));
5618 IkReal x1272=((cj5)*(sj7));
5619 IkReal x1273=((cj8)*(r20));
5620 IkReal x1274=((cj5)*(cj7));
5621 IkReal x1275=((cj7)*(sj5));
5622 if( IKabs(((gconst35)*(((((IkReal(-1.00000000000000))*(x1273)*(x1275)))+(((r22)*(x1274)))+(((IkReal(-1.00000000000000))*(r22)*(x1270)))+(((IkReal(-1.00000000000000))*(x1272)*(x1273)))+(((x1271)*(x1275)))+(((x1271)*(x1272))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst35)*(((((IkReal(-1.00000000000000))*(x1271)*(x1274)))+(((r22)*(x1272)))+(((r22)*(x1275)))+(((x1273)*(x1274)))+(((x1270)*(x1271)))+(((IkReal(-1.00000000000000))*(x1270)*(x1273))))))) < IKFAST_ATAN2_MAGTHRESH )
5623  continue;
5624 j4array[0]=IKatan2(((gconst35)*(((((IkReal(-1.00000000000000))*(x1273)*(x1275)))+(((r22)*(x1274)))+(((IkReal(-1.00000000000000))*(r22)*(x1270)))+(((IkReal(-1.00000000000000))*(x1272)*(x1273)))+(((x1271)*(x1275)))+(((x1271)*(x1272)))))), ((gconst35)*(((((IkReal(-1.00000000000000))*(x1271)*(x1274)))+(((r22)*(x1272)))+(((r22)*(x1275)))+(((x1273)*(x1274)))+(((x1270)*(x1271)))+(((IkReal(-1.00000000000000))*(x1270)*(x1273)))))));
5625 sj4array[0]=IKsin(j4array[0]);
5626 cj4array[0]=IKcos(j4array[0]);
5627 if( j4array[0] > IKPI )
5628 {
5629  j4array[0]-=IK2PI;
5630 }
5631 else if( j4array[0] < -IKPI )
5632 { j4array[0]+=IK2PI;
5633 }
5634 j4valid[0] = true;
5635 for(int ij4 = 0; ij4 < 1; ++ij4)
5636 {
5637 if( !j4valid[ij4] )
5638 {
5639  continue;
5640 }
5641 _ij4[0] = ij4; _ij4[1] = -1;
5642 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
5643 {
5644 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
5645 {
5646  j4valid[iij4]=false; _ij4[1] = iij4; break;
5647 }
5648 }
5649 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
5650 {
5651 IkReal evalcond[4];
5652 IkReal x1276=IKcos(j4);
5653 IkReal x1277=IKsin(j4);
5654 IkReal x1278=((IkReal(1.00000000000000))*(cj7));
5655 IkReal x1279=((cj8)*(r20));
5656 IkReal x1280=((cj3)*(r02));
5657 IkReal x1281=((IkReal(1.00000000000000))*(sj7));
5658 IkReal x1282=((sj3)*(sj7));
5659 IkReal x1283=((r21)*(sj8));
5660 IkReal x1284=((cj8)*(r10));
5661 IkReal x1285=((sj5)*(x1276));
5662 IkReal x1286=((cj5)*(x1277));
5663 IkReal x1287=((r11)*(sj3)*(sj8));
5664 IkReal x1288=((cj3)*(cj8)*(r00));
5665 IkReal x1289=((cj5)*(x1276));
5666 IkReal x1290=((cj3)*(r01)*(sj8));
5667 IkReal x1291=((sj5)*(x1277));
5668 IkReal x1292=((x1285)+(x1286));
5669 evalcond[0]=((((IkReal(-1.00000000000000))*(x1289)))+(x1291)+(((IkReal(-1.00000000000000))*(r22)*(x1281)))+(((cj7)*(x1283)))+(((IkReal(-1.00000000000000))*(x1278)*(x1279))));
5670 evalcond[1]=((x1292)+(((IkReal(-1.00000000000000))*(x1279)*(x1281)))+(((cj7)*(r22)))+(((sj7)*(x1283))));
5671 evalcond[2]=((x1292)+(((IkReal(-1.00000000000000))*(x1278)*(x1290)))+(((cj7)*(x1288)))+(((cj7)*(sj3)*(x1284)))+(((IkReal(-1.00000000000000))*(x1278)*(x1287)))+(((sj7)*(x1280)))+(((r12)*(x1282))));
5672 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1278)))+(x1289)+(((IkReal(-1.00000000000000))*(x1281)*(x1290)))+(((IkReal(-1.00000000000000))*(x1278)*(x1280)))+(((IkReal(-1.00000000000000))*(x1291)))+(((x1282)*(x1284)))+(((sj7)*(x1288)))+(((IkReal(-1.00000000000000))*(x1281)*(x1287))));
5673 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
5674 {
5675 continue;
5676 }
5677 }
5678 
5679 {
5680 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5681 vinfos[0].jointtype = 1;
5682 vinfos[0].foffset = j3;
5683 vinfos[0].indices[0] = _ij3[0];
5684 vinfos[0].indices[1] = _ij3[1];
5685 vinfos[0].maxsolutions = _nj3;
5686 vinfos[1].jointtype = 1;
5687 vinfos[1].foffset = j4;
5688 vinfos[1].indices[0] = _ij4[0];
5689 vinfos[1].indices[1] = _ij4[1];
5690 vinfos[1].maxsolutions = _nj4;
5691 vinfos[2].jointtype = 1;
5692 vinfos[2].foffset = j5;
5693 vinfos[2].indices[0] = _ij5[0];
5694 vinfos[2].indices[1] = _ij5[1];
5695 vinfos[2].maxsolutions = _nj5;
5696 vinfos[3].jointtype = 1;
5697 vinfos[3].foffset = j6;
5698 vinfos[3].indices[0] = _ij6[0];
5699 vinfos[3].indices[1] = _ij6[1];
5700 vinfos[3].maxsolutions = _nj6;
5701 vinfos[4].jointtype = 1;
5702 vinfos[4].foffset = j7;
5703 vinfos[4].indices[0] = _ij7[0];
5704 vinfos[4].indices[1] = _ij7[1];
5705 vinfos[4].maxsolutions = _nj7;
5706 vinfos[5].jointtype = 1;
5707 vinfos[5].foffset = j8;
5708 vinfos[5].indices[0] = _ij8[0];
5709 vinfos[5].indices[1] = _ij8[1];
5710 vinfos[5].maxsolutions = _nj8;
5711 std::vector<int> vfree(0);
5712 solutions.AddSolution(vinfos,vfree);
5713 }
5714 }
5715 }
5716 
5717 }
5718 
5719 }
5720 }
5721 }
5722 
5723 }
5724 
5725 }
5726 
5727 } else
5728 {
5729 IkReal x1293=((IkReal(1.00000000000000))*(sj7));
5730 IkReal x1294=((npy)*(sj8));
5731 IkReal x1295=((cj8)*(npx));
5732 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
5733 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
5734 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
5735 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(cj7)*(x1295)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x1293)))+(((IkReal(0.250000000000000))*(cj5)))+(((cj7)*(x1294))));
5736 evalcond[4]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(0.250000000000000))*(sj5)))+(((sj7)*(x1294)))+(((IkReal(-1.00000000000000))*(x1293)*(x1295)))+(((cj7)*(npz))));
5737 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 )
5738 {
5739 {
5740 IkReal dummyeval[1];
5741 IkReal gconst39;
5742 IkReal x1296=(cj8)*(cj8);
5743 IkReal x1297=(sj8)*(sj8);
5744 IkReal x1298=((IkReal(2.00000000000000))*(cj8)*(sj8));
5745 IkReal x1299=((IkReal(1.00000000000000))*(x1296));
5746 IkReal x1300=((IkReal(1.00000000000000))*(x1297));
5747 gconst39=IKsign(((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1298)))+(((IkReal(-1.00000000000000))*(x1299)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1298)))+(((IkReal(-1.00000000000000))*(x1299)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1300)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1300)*((r00)*(r00))))));
5748 IkReal x1301=(cj8)*(cj8);
5749 IkReal x1302=(sj8)*(sj8);
5750 IkReal x1303=((IkReal(2.00000000000000))*(cj8)*(sj8));
5751 IkReal x1304=((IkReal(1.00000000000000))*(x1301));
5752 IkReal x1305=((IkReal(1.00000000000000))*(x1302));
5753 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1305)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1305)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1303)))+(((IkReal(-1.00000000000000))*(x1304)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1304)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1303))));
5754 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5755 {
5756 {
5757 IkReal dummyeval[1];
5758 IkReal gconst41;
5759 gconst41=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
5760 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
5761 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5762 {
5763 {
5764 IkReal dummyeval[1];
5765 IkReal gconst40;
5766 IkReal x1306=(sj8)*(sj8);
5767 IkReal x1307=(cj8)*(cj8);
5768 IkReal x1308=((sj7)*(sj8));
5769 IkReal x1309=((IkReal(1.00000000000000))*(r02));
5770 IkReal x1310=((r01)*(r10));
5771 IkReal x1311=((cj8)*(sj7));
5772 IkReal x1312=((cj7)*(x1306));
5773 IkReal x1313=((IkReal(1.00000000000000))*(r00)*(r11));
5774 IkReal x1314=((cj7)*(x1307));
5775 gconst40=IKsign(((((x1310)*(x1312)))+(((x1310)*(x1314)))+(((IkReal(-1.00000000000000))*(x1313)*(x1314)))+(((r01)*(r12)*(x1311)))+(((IkReal(-1.00000000000000))*(r10)*(x1308)*(x1309)))+(((IkReal(-1.00000000000000))*(r11)*(x1309)*(x1311)))+(((r00)*(r12)*(x1308)))+(((IkReal(-1.00000000000000))*(x1312)*(x1313)))));
5776 IkReal x1315=(sj8)*(sj8);
5777 IkReal x1316=(cj8)*(cj8);
5778 IkReal x1317=((sj7)*(sj8));
5779 IkReal x1318=((IkReal(1.00000000000000))*(r02));
5780 IkReal x1319=((r01)*(r10));
5781 IkReal x1320=((cj8)*(sj7));
5782 IkReal x1321=((cj7)*(x1315));
5783 IkReal x1322=((IkReal(1.00000000000000))*(r00)*(r11));
5784 IkReal x1323=((cj7)*(x1316));
5785 dummyeval[0]=((((IkReal(-1.00000000000000))*(r11)*(x1318)*(x1320)))+(((IkReal(-1.00000000000000))*(x1322)*(x1323)))+(((r01)*(r12)*(x1320)))+(((x1319)*(x1321)))+(((x1319)*(x1323)))+(((IkReal(-1.00000000000000))*(x1321)*(x1322)))+(((r00)*(r12)*(x1317)))+(((IkReal(-1.00000000000000))*(r10)*(x1317)*(x1318))));
5786 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5787 {
5788 continue;
5789 
5790 } else
5791 {
5792 {
5793 IkReal j3array[1], cj3array[1], sj3array[1];
5794 bool j3valid[1]={false};
5795 _nj3 = 1;
5796 IkReal x1324=((cj7)*(cj8));
5797 IkReal x1325=((IkReal(1.00000000000000))*(cj7)*(sj8));
5798 if( IKabs(((gconst40)*(((((r10)*(x1324)))+(((IkReal(-1.00000000000000))*(r11)*(x1325)))+(((r12)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst40)*(((((r00)*(x1324)))+(((IkReal(-1.00000000000000))*(r01)*(x1325)))+(((r02)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH )
5799  continue;
5800 j3array[0]=IKatan2(((gconst40)*(((((r10)*(x1324)))+(((IkReal(-1.00000000000000))*(r11)*(x1325)))+(((r12)*(sj7)))))), ((gconst40)*(((((r00)*(x1324)))+(((IkReal(-1.00000000000000))*(r01)*(x1325)))+(((r02)*(sj7)))))));
5801 sj3array[0]=IKsin(j3array[0]);
5802 cj3array[0]=IKcos(j3array[0]);
5803 if( j3array[0] > IKPI )
5804 {
5805  j3array[0]-=IK2PI;
5806 }
5807 else if( j3array[0] < -IKPI )
5808 { j3array[0]+=IK2PI;
5809 }
5810 j3valid[0] = true;
5811 for(int ij3 = 0; ij3 < 1; ++ij3)
5812 {
5813 if( !j3valid[ij3] )
5814 {
5815  continue;
5816 }
5817 _ij3[0] = ij3; _ij3[1] = -1;
5818 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
5819 {
5820 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
5821 {
5822  j3valid[iij3]=false; _ij3[1] = iij3; break;
5823 }
5824 }
5825 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
5826 {
5827 IkReal evalcond[4];
5828 IkReal x1326=IKsin(j3);
5829 IkReal x1327=IKcos(j3);
5830 IkReal x1328=((IkReal(1.00000000000000))*(sj8));
5831 IkReal x1329=((IkReal(1.00000000000000))*(cj8));
5832 IkReal x1330=((r01)*(sj8));
5833 IkReal x1331=((cj8)*(r10));
5834 IkReal x1332=((sj7)*(x1327));
5835 IkReal x1333=((cj7)*(x1326));
5836 IkReal x1334=((r00)*(x1326));
5837 IkReal x1335=((sj7)*(x1326));
5838 IkReal x1336=((cj7)*(x1327));
5839 evalcond[0]=((IkReal(-1.00000000000000))+(((cj8)*(r01)*(x1326)))+(((IkReal(-1.00000000000000))*(r11)*(x1327)*(x1329)))+(((sj8)*(x1334)))+(((IkReal(-1.00000000000000))*(r10)*(x1327)*(x1328))));
5840 evalcond[1]=((((IkReal(-1.00000000000000))*(r01)*(x1327)*(x1329)))+(((IkReal(-1.00000000000000))*(r00)*(x1327)*(x1328)))+(((IkReal(-1.00000000000000))*(r11)*(x1326)*(x1329)))+(((IkReal(-1.00000000000000))*(r10)*(x1326)*(x1328))));
5841 evalcond[2]=((((r12)*(x1332)))+(((x1331)*(x1336)))+(((IkReal(-1.00000000000000))*(r11)*(x1328)*(x1336)))+(((IkReal(-1.00000000000000))*(r00)*(x1329)*(x1333)))+(((x1330)*(x1333)))+(((IkReal(-1.00000000000000))*(r02)*(x1335))));
5842 evalcond[3]=((((x1331)*(x1332)))+(((IkReal(-1.00000000000000))*(r11)*(x1328)*(x1332)))+(((IkReal(-1.00000000000000))*(sj7)*(x1329)*(x1334)))+(((IkReal(-1.00000000000000))*(r12)*(x1336)))+(((x1330)*(x1335)))+(((r02)*(x1333))));
5843 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
5844 {
5845 continue;
5846 }
5847 }
5848 
5849 {
5850 IkReal dummyeval[1];
5851 IkReal gconst42;
5852 gconst42=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
5853 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
5854 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5855 {
5856 {
5857 IkReal dummyeval[1];
5858 IkReal gconst43;
5859 gconst43=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
5860 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
5861 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
5862 {
5863 continue;
5864 
5865 } else
5866 {
5867 {
5868 IkReal j4array[1], cj4array[1], sj4array[1];
5869 bool j4valid[1]={false};
5870 _nj4 = 1;
5871 IkReal x1337=((cj3)*(r01));
5872 IkReal x1338=((cj5)*(sj7));
5873 IkReal x1339=((r11)*(sj3));
5874 IkReal x1340=((r10)*(sj3));
5875 IkReal x1341=((cj3)*(r00));
5876 IkReal x1342=((r12)*(sj3));
5877 IkReal x1343=((sj5)*(sj7));
5878 IkReal x1344=((cj7)*(sj5));
5879 IkReal x1345=((cj3)*(r02)*(sj7));
5880 IkReal x1346=((IkReal(1.00000000000000))*(x1344));
5881 IkReal x1347=((cj5)*(cj7)*(cj8));
5882 IkReal x1348=((IkReal(1.00000000000000))*(cj5)*(cj7)*(sj8));
5883 if( IKabs(((gconst43)*(((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x1346)))+(((x1340)*(x1347)))+(((x1341)*(x1347)))+(((x1338)*(x1342)))+(((IkReal(-1.00000000000000))*(x1339)*(x1348)))+(((r21)*(sj8)*(x1344)))+(((IkReal(-1.00000000000000))*(r22)*(x1343)))+(((IkReal(-1.00000000000000))*(x1337)*(x1348)))+(((cj3)*(r02)*(x1338))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((cj8)*(x1340)*(x1344)))+(((IkReal(-1.00000000000000))*(r21)*(x1348)))+(((cj8)*(x1341)*(x1344)))+(((IkReal(-1.00000000000000))*(sj8)*(x1337)*(x1346)))+(((IkReal(-1.00000000000000))*(sj8)*(x1339)*(x1346)))+(((cj3)*(r02)*(x1343)))+(((x1342)*(x1343)))+(((r22)*(x1338)))+(((r20)*(x1347))))))) < IKFAST_ATAN2_MAGTHRESH )
5884  continue;
5885 j4array[0]=IKatan2(((gconst43)*(((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x1346)))+(((x1340)*(x1347)))+(((x1341)*(x1347)))+(((x1338)*(x1342)))+(((IkReal(-1.00000000000000))*(x1339)*(x1348)))+(((r21)*(sj8)*(x1344)))+(((IkReal(-1.00000000000000))*(r22)*(x1343)))+(((IkReal(-1.00000000000000))*(x1337)*(x1348)))+(((cj3)*(r02)*(x1338)))))), ((gconst43)*(((((cj8)*(x1340)*(x1344)))+(((IkReal(-1.00000000000000))*(r21)*(x1348)))+(((cj8)*(x1341)*(x1344)))+(((IkReal(-1.00000000000000))*(sj8)*(x1337)*(x1346)))+(((IkReal(-1.00000000000000))*(sj8)*(x1339)*(x1346)))+(((cj3)*(r02)*(x1343)))+(((x1342)*(x1343)))+(((r22)*(x1338)))+(((r20)*(x1347)))))));
5886 sj4array[0]=IKsin(j4array[0]);
5887 cj4array[0]=IKcos(j4array[0]);
5888 if( j4array[0] > IKPI )
5889 {
5890  j4array[0]-=IK2PI;
5891 }
5892 else if( j4array[0] < -IKPI )
5893 { j4array[0]+=IK2PI;
5894 }
5895 j4valid[0] = true;
5896 for(int ij4 = 0; ij4 < 1; ++ij4)
5897 {
5898 if( !j4valid[ij4] )
5899 {
5900  continue;
5901 }
5902 _ij4[0] = ij4; _ij4[1] = -1;
5903 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
5904 {
5905 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
5906 {
5907  j4valid[iij4]=false; _ij4[1] = iij4; break;
5908 }
5909 }
5910 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
5911 {
5912 IkReal evalcond[4];
5913 IkReal x1349=IKcos(j4);
5914 IkReal x1350=IKsin(j4);
5915 IkReal x1351=((IkReal(1.00000000000000))*(cj7));
5916 IkReal x1352=((cj8)*(r20));
5917 IkReal x1353=((cj3)*(r02));
5918 IkReal x1354=((IkReal(1.00000000000000))*(sj7));
5919 IkReal x1355=((sj3)*(sj7));
5920 IkReal x1356=((r21)*(sj8));
5921 IkReal x1357=((IkReal(1.00000000000000))*(cj5));
5922 IkReal x1358=((cj8)*(r10));
5923 IkReal x1359=((sj5)*(x1350));
5924 IkReal x1360=((sj5)*(x1349));
5925 IkReal x1361=((r11)*(sj3)*(sj8));
5926 IkReal x1362=((cj3)*(cj8)*(r00));
5927 IkReal x1363=((cj3)*(r01)*(sj8));
5928 IkReal x1364=((x1349)*(x1357));
5929 evalcond[0]=((x1359)+(((IkReal(-1.00000000000000))*(r22)*(x1354)))+(((cj7)*(x1356)))+(((IkReal(-1.00000000000000))*(x1351)*(x1352)))+(((IkReal(-1.00000000000000))*(x1364))));
5930 evalcond[1]=((((IkReal(-1.00000000000000))*(x1352)*(x1354)))+(((IkReal(-1.00000000000000))*(x1360)))+(((IkReal(-1.00000000000000))*(x1350)*(x1357)))+(((cj7)*(r22)))+(((sj7)*(x1356))));
5931 evalcond[2]=((x1360)+(((cj5)*(x1350)))+(((cj7)*(x1362)))+(((cj7)*(sj3)*(x1358)))+(((r12)*(x1355)))+(((IkReal(-1.00000000000000))*(x1351)*(x1363)))+(((IkReal(-1.00000000000000))*(x1351)*(x1361)))+(((sj7)*(x1353))));
5932 evalcond[3]=((x1359)+(((x1355)*(x1358)))+(((IkReal(-1.00000000000000))*(x1354)*(x1361)))+(((IkReal(-1.00000000000000))*(x1354)*(x1363)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1351)))+(((IkReal(-1.00000000000000))*(x1351)*(x1353)))+(((IkReal(-1.00000000000000))*(x1364)))+(((sj7)*(x1362))));
5933 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
5934 {
5935 continue;
5936 }
5937 }
5938 
5939 {
5940 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5941 vinfos[0].jointtype = 1;
5942 vinfos[0].foffset = j3;
5943 vinfos[0].indices[0] = _ij3[0];
5944 vinfos[0].indices[1] = _ij3[1];
5945 vinfos[0].maxsolutions = _nj3;
5946 vinfos[1].jointtype = 1;
5947 vinfos[1].foffset = j4;
5948 vinfos[1].indices[0] = _ij4[0];
5949 vinfos[1].indices[1] = _ij4[1];
5950 vinfos[1].maxsolutions = _nj4;
5951 vinfos[2].jointtype = 1;
5952 vinfos[2].foffset = j5;
5953 vinfos[2].indices[0] = _ij5[0];
5954 vinfos[2].indices[1] = _ij5[1];
5955 vinfos[2].maxsolutions = _nj5;
5956 vinfos[3].jointtype = 1;
5957 vinfos[3].foffset = j6;
5958 vinfos[3].indices[0] = _ij6[0];
5959 vinfos[3].indices[1] = _ij6[1];
5960 vinfos[3].maxsolutions = _nj6;
5961 vinfos[4].jointtype = 1;
5962 vinfos[4].foffset = j7;
5963 vinfos[4].indices[0] = _ij7[0];
5964 vinfos[4].indices[1] = _ij7[1];
5965 vinfos[4].maxsolutions = _nj7;
5966 vinfos[5].jointtype = 1;
5967 vinfos[5].foffset = j8;
5968 vinfos[5].indices[0] = _ij8[0];
5969 vinfos[5].indices[1] = _ij8[1];
5970 vinfos[5].maxsolutions = _nj8;
5971 std::vector<int> vfree(0);
5972 solutions.AddSolution(vinfos,vfree);
5973 }
5974 }
5975 }
5976 
5977 }
5978 
5979 }
5980 
5981 } else
5982 {
5983 {
5984 IkReal j4array[1], cj4array[1], sj4array[1];
5985 bool j4valid[1]={false};
5986 _nj4 = 1;
5987 IkReal x1365=((cj7)*(sj5));
5988 IkReal x1366=((r21)*(sj8));
5989 IkReal x1367=((cj5)*(cj7));
5990 IkReal x1368=((cj8)*(r20));
5991 IkReal x1369=((sj5)*(sj7));
5992 IkReal x1370=((IkReal(1.00000000000000))*(cj5)*(sj7));
5993 if( IKabs(((gconst42)*(((((r22)*(x1367)))+(((r22)*(x1369)))+(((cj5)*(sj7)*(x1366)))+(((IkReal(-1.00000000000000))*(x1365)*(x1366)))+(((x1365)*(x1368)))+(((IkReal(-1.00000000000000))*(x1368)*(x1370))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(x1368)*(x1369)))+(((x1366)*(x1367)))+(((x1366)*(x1369)))+(((r22)*(x1365)))+(((IkReal(-1.00000000000000))*(r22)*(x1370)))+(((IkReal(-1.00000000000000))*(x1367)*(x1368))))))) < IKFAST_ATAN2_MAGTHRESH )
5994  continue;
5995 j4array[0]=IKatan2(((gconst42)*(((((r22)*(x1367)))+(((r22)*(x1369)))+(((cj5)*(sj7)*(x1366)))+(((IkReal(-1.00000000000000))*(x1365)*(x1366)))+(((x1365)*(x1368)))+(((IkReal(-1.00000000000000))*(x1368)*(x1370)))))), ((gconst42)*(((((IkReal(-1.00000000000000))*(x1368)*(x1369)))+(((x1366)*(x1367)))+(((x1366)*(x1369)))+(((r22)*(x1365)))+(((IkReal(-1.00000000000000))*(r22)*(x1370)))+(((IkReal(-1.00000000000000))*(x1367)*(x1368)))))));
5996 sj4array[0]=IKsin(j4array[0]);
5997 cj4array[0]=IKcos(j4array[0]);
5998 if( j4array[0] > IKPI )
5999 {
6000  j4array[0]-=IK2PI;
6001 }
6002 else if( j4array[0] < -IKPI )
6003 { j4array[0]+=IK2PI;
6004 }
6005 j4valid[0] = true;
6006 for(int ij4 = 0; ij4 < 1; ++ij4)
6007 {
6008 if( !j4valid[ij4] )
6009 {
6010  continue;
6011 }
6012 _ij4[0] = ij4; _ij4[1] = -1;
6013 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
6014 {
6015 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
6016 {
6017  j4valid[iij4]=false; _ij4[1] = iij4; break;
6018 }
6019 }
6020 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
6021 {
6022 IkReal evalcond[4];
6023 IkReal x1371=IKcos(j4);
6024 IkReal x1372=IKsin(j4);
6025 IkReal x1373=((IkReal(1.00000000000000))*(cj7));
6026 IkReal x1374=((cj8)*(r20));
6027 IkReal x1375=((cj3)*(r02));
6028 IkReal x1376=((IkReal(1.00000000000000))*(sj7));
6029 IkReal x1377=((sj3)*(sj7));
6030 IkReal x1378=((r21)*(sj8));
6031 IkReal x1379=((IkReal(1.00000000000000))*(cj5));
6032 IkReal x1380=((cj8)*(r10));
6033 IkReal x1381=((sj5)*(x1372));
6034 IkReal x1382=((sj5)*(x1371));
6035 IkReal x1383=((r11)*(sj3)*(sj8));
6036 IkReal x1384=((cj3)*(cj8)*(r00));
6037 IkReal x1385=((cj3)*(r01)*(sj8));
6038 IkReal x1386=((x1371)*(x1379));
6039 evalcond[0]=((((IkReal(-1.00000000000000))*(x1386)))+(x1381)+(((IkReal(-1.00000000000000))*(r22)*(x1376)))+(((IkReal(-1.00000000000000))*(x1373)*(x1374)))+(((cj7)*(x1378))));
6040 evalcond[1]=((((IkReal(-1.00000000000000))*(x1372)*(x1379)))+(((IkReal(-1.00000000000000))*(x1374)*(x1376)))+(((IkReal(-1.00000000000000))*(x1382)))+(((sj7)*(x1378)))+(((cj7)*(r22))));
6041 evalcond[2]=((x1382)+(((IkReal(-1.00000000000000))*(x1373)*(x1385)))+(((IkReal(-1.00000000000000))*(x1373)*(x1383)))+(((cj5)*(x1372)))+(((r12)*(x1377)))+(((cj7)*(x1384)))+(((cj7)*(sj3)*(x1380)))+(((sj7)*(x1375))));
6042 evalcond[3]=((((IkReal(-1.00000000000000))*(x1386)))+(x1381)+(((sj7)*(x1384)))+(((IkReal(-1.00000000000000))*(x1376)*(x1383)))+(((IkReal(-1.00000000000000))*(x1376)*(x1385)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1373)))+(((x1377)*(x1380)))+(((IkReal(-1.00000000000000))*(x1373)*(x1375))));
6043 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
6044 {
6045 continue;
6046 }
6047 }
6048 
6049 {
6050 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6051 vinfos[0].jointtype = 1;
6052 vinfos[0].foffset = j3;
6053 vinfos[0].indices[0] = _ij3[0];
6054 vinfos[0].indices[1] = _ij3[1];
6055 vinfos[0].maxsolutions = _nj3;
6056 vinfos[1].jointtype = 1;
6057 vinfos[1].foffset = j4;
6058 vinfos[1].indices[0] = _ij4[0];
6059 vinfos[1].indices[1] = _ij4[1];
6060 vinfos[1].maxsolutions = _nj4;
6061 vinfos[2].jointtype = 1;
6062 vinfos[2].foffset = j5;
6063 vinfos[2].indices[0] = _ij5[0];
6064 vinfos[2].indices[1] = _ij5[1];
6065 vinfos[2].maxsolutions = _nj5;
6066 vinfos[3].jointtype = 1;
6067 vinfos[3].foffset = j6;
6068 vinfos[3].indices[0] = _ij6[0];
6069 vinfos[3].indices[1] = _ij6[1];
6070 vinfos[3].maxsolutions = _nj6;
6071 vinfos[4].jointtype = 1;
6072 vinfos[4].foffset = j7;
6073 vinfos[4].indices[0] = _ij7[0];
6074 vinfos[4].indices[1] = _ij7[1];
6075 vinfos[4].maxsolutions = _nj7;
6076 vinfos[5].jointtype = 1;
6077 vinfos[5].foffset = j8;
6078 vinfos[5].indices[0] = _ij8[0];
6079 vinfos[5].indices[1] = _ij8[1];
6080 vinfos[5].maxsolutions = _nj8;
6081 std::vector<int> vfree(0);
6082 solutions.AddSolution(vinfos,vfree);
6083 }
6084 }
6085 }
6086 
6087 }
6088 
6089 }
6090 }
6091 }
6092 
6093 }
6094 
6095 }
6096 
6097 } else
6098 {
6099 {
6100 IkReal j4array[1], cj4array[1], sj4array[1];
6101 bool j4valid[1]={false};
6102 _nj4 = 1;
6103 IkReal x1387=((cj7)*(sj5));
6104 IkReal x1388=((r21)*(sj8));
6105 IkReal x1389=((cj5)*(cj7));
6106 IkReal x1390=((cj8)*(r20));
6107 IkReal x1391=((sj5)*(sj7));
6108 IkReal x1392=((IkReal(1.00000000000000))*(cj5)*(sj7));
6109 if( IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(x1387)*(x1388)))+(((IkReal(-1.00000000000000))*(x1390)*(x1392)))+(((x1387)*(x1390)))+(((cj5)*(sj7)*(x1388)))+(((r22)*(x1389)))+(((r22)*(x1391))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst41)*(((((x1388)*(x1391)))+(((IkReal(-1.00000000000000))*(x1390)*(x1391)))+(((x1388)*(x1389)))+(((IkReal(-1.00000000000000))*(x1389)*(x1390)))+(((IkReal(-1.00000000000000))*(r22)*(x1392)))+(((r22)*(x1387))))))) < IKFAST_ATAN2_MAGTHRESH )
6110  continue;
6111 j4array[0]=IKatan2(((gconst41)*(((((IkReal(-1.00000000000000))*(x1387)*(x1388)))+(((IkReal(-1.00000000000000))*(x1390)*(x1392)))+(((x1387)*(x1390)))+(((cj5)*(sj7)*(x1388)))+(((r22)*(x1389)))+(((r22)*(x1391)))))), ((gconst41)*(((((x1388)*(x1391)))+(((IkReal(-1.00000000000000))*(x1390)*(x1391)))+(((x1388)*(x1389)))+(((IkReal(-1.00000000000000))*(x1389)*(x1390)))+(((IkReal(-1.00000000000000))*(r22)*(x1392)))+(((r22)*(x1387)))))));
6112 sj4array[0]=IKsin(j4array[0]);
6113 cj4array[0]=IKcos(j4array[0]);
6114 if( j4array[0] > IKPI )
6115 {
6116  j4array[0]-=IK2PI;
6117 }
6118 else if( j4array[0] < -IKPI )
6119 { j4array[0]+=IK2PI;
6120 }
6121 j4valid[0] = true;
6122 for(int ij4 = 0; ij4 < 1; ++ij4)
6123 {
6124 if( !j4valid[ij4] )
6125 {
6126  continue;
6127 }
6128 _ij4[0] = ij4; _ij4[1] = -1;
6129 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
6130 {
6131 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
6132 {
6133  j4valid[iij4]=false; _ij4[1] = iij4; break;
6134 }
6135 }
6136 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
6137 {
6138 IkReal evalcond[2];
6139 IkReal x1393=IKcos(j4);
6140 IkReal x1394=IKsin(j4);
6141 IkReal x1395=((IkReal(1.00000000000000))*(cj5));
6142 IkReal x1396=((r21)*(sj8));
6143 IkReal x1397=((IkReal(1.00000000000000))*(cj8)*(r20));
6144 evalcond[0]=((((IkReal(-1.00000000000000))*(x1393)*(x1395)))+(((cj7)*(x1396)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((sj5)*(x1394)))+(((IkReal(-1.00000000000000))*(cj7)*(x1397))));
6145 evalcond[1]=((((IkReal(-1.00000000000000))*(sj7)*(x1397)))+(((IkReal(-1.00000000000000))*(sj5)*(x1393)))+(((sj7)*(x1396)))+(((IkReal(-1.00000000000000))*(x1394)*(x1395)))+(((cj7)*(r22))));
6146 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
6147 {
6148 continue;
6149 }
6150 }
6151 
6152 {
6153 IkReal dummyeval[1];
6154 IkReal gconst44;
6155 IkReal x1398=(cj8)*(cj8);
6156 IkReal x1399=(sj8)*(sj8);
6157 IkReal x1400=((IkReal(2.00000000000000))*(cj8)*(sj8));
6158 IkReal x1401=((IkReal(1.00000000000000))*(x1398));
6159 IkReal x1402=((IkReal(1.00000000000000))*(x1399));
6160 gconst44=IKsign(((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1400)))+(((IkReal(-1.00000000000000))*(x1401)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1402)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1401)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1400)))+(((IkReal(-1.00000000000000))*(x1402)*((r10)*(r10))))));
6161 IkReal x1403=(cj8)*(cj8);
6162 IkReal x1404=(sj8)*(sj8);
6163 IkReal x1405=((IkReal(2.00000000000000))*(cj8)*(sj8));
6164 IkReal x1406=((IkReal(1.00000000000000))*(x1403));
6165 IkReal x1407=((IkReal(1.00000000000000))*(x1404));
6166 dummyeval[0]=((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1405)))+(((IkReal(-1.00000000000000))*(x1406)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1407)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1407)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1406)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1405))));
6167 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6168 {
6169 {
6170 IkReal dummyeval[1];
6171 IkReal gconst45;
6172 IkReal x1408=(sj8)*(sj8);
6173 IkReal x1409=(cj8)*(cj8);
6174 IkReal x1410=((sj7)*(sj8));
6175 IkReal x1411=((IkReal(1.00000000000000))*(r02));
6176 IkReal x1412=((r01)*(r10));
6177 IkReal x1413=((cj8)*(sj7));
6178 IkReal x1414=((cj7)*(x1408));
6179 IkReal x1415=((IkReal(1.00000000000000))*(r00)*(r11));
6180 IkReal x1416=((cj7)*(x1409));
6181 gconst45=IKsign(((((IkReal(-1.00000000000000))*(x1415)*(x1416)))+(((x1412)*(x1414)))+(((x1412)*(x1416)))+(((IkReal(-1.00000000000000))*(r11)*(x1411)*(x1413)))+(((IkReal(-1.00000000000000))*(x1414)*(x1415)))+(((r01)*(r12)*(x1413)))+(((IkReal(-1.00000000000000))*(r10)*(x1410)*(x1411)))+(((r00)*(r12)*(x1410)))));
6182 IkReal x1417=(sj8)*(sj8);
6183 IkReal x1418=(cj8)*(cj8);
6184 IkReal x1419=((sj7)*(sj8));
6185 IkReal x1420=((IkReal(1.00000000000000))*(r02));
6186 IkReal x1421=((r01)*(r10));
6187 IkReal x1422=((cj8)*(sj7));
6188 IkReal x1423=((cj7)*(x1417));
6189 IkReal x1424=((IkReal(1.00000000000000))*(r00)*(r11));
6190 IkReal x1425=((cj7)*(x1418));
6191 dummyeval[0]=((((r01)*(r12)*(x1422)))+(((IkReal(-1.00000000000000))*(x1424)*(x1425)))+(((IkReal(-1.00000000000000))*(x1423)*(x1424)))+(((IkReal(-1.00000000000000))*(r11)*(x1420)*(x1422)))+(((r00)*(r12)*(x1419)))+(((x1421)*(x1423)))+(((x1421)*(x1425)))+(((IkReal(-1.00000000000000))*(r10)*(x1419)*(x1420))));
6192 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6193 {
6194 continue;
6195 
6196 } else
6197 {
6198 {
6199 IkReal j3array[1], cj3array[1], sj3array[1];
6200 bool j3valid[1]={false};
6201 _nj3 = 1;
6202 IkReal x1426=((cj7)*(cj8));
6203 IkReal x1427=((IkReal(1.00000000000000))*(cj7)*(sj8));
6204 if( IKabs(((gconst45)*(((((IkReal(-1.00000000000000))*(r11)*(x1427)))+(((r10)*(x1426)))+(((r12)*(sj7))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst45)*(((((r00)*(x1426)))+(((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x1427))))))) < IKFAST_ATAN2_MAGTHRESH )
6205  continue;
6206 j3array[0]=IKatan2(((gconst45)*(((((IkReal(-1.00000000000000))*(r11)*(x1427)))+(((r10)*(x1426)))+(((r12)*(sj7)))))), ((gconst45)*(((((r00)*(x1426)))+(((r02)*(sj7)))+(((IkReal(-1.00000000000000))*(r01)*(x1427)))))));
6207 sj3array[0]=IKsin(j3array[0]);
6208 cj3array[0]=IKcos(j3array[0]);
6209 if( j3array[0] > IKPI )
6210 {
6211  j3array[0]-=IK2PI;
6212 }
6213 else if( j3array[0] < -IKPI )
6214 { j3array[0]+=IK2PI;
6215 }
6216 j3valid[0] = true;
6217 for(int ij3 = 0; ij3 < 1; ++ij3)
6218 {
6219 if( !j3valid[ij3] )
6220 {
6221  continue;
6222 }
6223 _ij3[0] = ij3; _ij3[1] = -1;
6224 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6225 {
6226 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6227 {
6228  j3valid[iij3]=false; _ij3[1] = iij3; break;
6229 }
6230 }
6231 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6232 {
6233 IkReal evalcond[6];
6234 IkReal x1428=IKsin(j3);
6235 IkReal x1429=IKcos(j3);
6236 IkReal x1430=((r01)*(sj8));
6237 IkReal x1431=((cj8)*(r00));
6238 IkReal x1432=((r00)*(sj8));
6239 IkReal x1433=((cj8)*(r11));
6240 IkReal x1434=((r11)*(sj8));
6241 IkReal x1435=((r10)*(sj8));
6242 IkReal x1436=((cj8)*(r10));
6243 IkReal x1437=((cj7)*(x1428));
6244 IkReal x1438=((sj7)*(x1429));
6245 IkReal x1439=((IkReal(1.00000000000000))*(x1428));
6246 IkReal x1440=((IkReal(1.00000000000000))*(x1429));
6247 IkReal x1441=((cj8)*(x1428));
6248 IkReal x1442=((IkReal(1.00000000000000))*(x1434));
6249 IkReal x1443=((sj7)*(x1428));
6250 IkReal x1444=((cj7)*(x1429));
6251 evalcond[0]=((IkReal(-1.00000000000000))+(((x1428)*(x1432)))+(((IkReal(-1.00000000000000))*(x1433)*(x1440)))+(((IkReal(-1.00000000000000))*(x1435)*(x1440)))+(((r01)*(x1441))));
6252 evalcond[1]=((((IkReal(-1.00000000000000))*(x1435)*(x1439)))+(((IkReal(-1.00000000000000))*(x1432)*(x1440)))+(((IkReal(-1.00000000000000))*(x1433)*(x1439)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1440))));
6253 evalcond[2]=((((x1430)*(x1437)))+(((r12)*(x1438)))+(((IkReal(-1.00000000000000))*(x1431)*(x1437)))+(((x1436)*(x1444)))+(((IkReal(-1.00000000000000))*(cj7)*(x1434)*(x1440)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1439))));
6254 evalcond[3]=((((r02)*(x1437)))+(((x1436)*(x1438)))+(((IkReal(-1.00000000000000))*(x1438)*(x1442)))+(((x1430)*(x1443)))+(((IkReal(-1.00000000000000))*(sj7)*(x1431)*(x1439)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1440))));
6255 evalcond[4]=((((r12)*(x1443)))+(((r02)*(x1438)))+(((x1436)*(x1437)))+(((IkReal(-1.00000000000000))*(x1437)*(x1442)))+(((cj5)*(sj4)))+(((IkReal(-1.00000000000000))*(cj7)*(x1430)*(x1440)))+(((cj4)*(sj5)))+(((x1431)*(x1444))));
6256 evalcond[5]=((((IkReal(-1.00000000000000))*(sj7)*(x1434)*(x1439)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1440)))+(((x1436)*(x1443)))+(((sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(x1430)*(x1438)))+(((IkReal(-1.00000000000000))*(r12)*(x1437)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)))+(((x1431)*(x1438))));
6257 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
6258 {
6259 continue;
6260 }
6261 }
6262 
6263 {
6264 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6265 vinfos[0].jointtype = 1;
6266 vinfos[0].foffset = j3;
6267 vinfos[0].indices[0] = _ij3[0];
6268 vinfos[0].indices[1] = _ij3[1];
6269 vinfos[0].maxsolutions = _nj3;
6270 vinfos[1].jointtype = 1;
6271 vinfos[1].foffset = j4;
6272 vinfos[1].indices[0] = _ij4[0];
6273 vinfos[1].indices[1] = _ij4[1];
6274 vinfos[1].maxsolutions = _nj4;
6275 vinfos[2].jointtype = 1;
6276 vinfos[2].foffset = j5;
6277 vinfos[2].indices[0] = _ij5[0];
6278 vinfos[2].indices[1] = _ij5[1];
6279 vinfos[2].maxsolutions = _nj5;
6280 vinfos[3].jointtype = 1;
6281 vinfos[3].foffset = j6;
6282 vinfos[3].indices[0] = _ij6[0];
6283 vinfos[3].indices[1] = _ij6[1];
6284 vinfos[3].maxsolutions = _nj6;
6285 vinfos[4].jointtype = 1;
6286 vinfos[4].foffset = j7;
6287 vinfos[4].indices[0] = _ij7[0];
6288 vinfos[4].indices[1] = _ij7[1];
6289 vinfos[4].maxsolutions = _nj7;
6290 vinfos[5].jointtype = 1;
6291 vinfos[5].foffset = j8;
6292 vinfos[5].indices[0] = _ij8[0];
6293 vinfos[5].indices[1] = _ij8[1];
6294 vinfos[5].maxsolutions = _nj8;
6295 std::vector<int> vfree(0);
6296 solutions.AddSolution(vinfos,vfree);
6297 }
6298 }
6299 }
6300 
6301 }
6302 
6303 }
6304 
6305 } else
6306 {
6307 {
6308 IkReal j3array[1], cj3array[1], sj3array[1];
6309 bool j3valid[1]={false};
6310 _nj3 = 1;
6311 if( IKabs(((gconst44)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst44)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
6312  continue;
6313 j3array[0]=IKatan2(((gconst44)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst44)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
6314 sj3array[0]=IKsin(j3array[0]);
6315 cj3array[0]=IKcos(j3array[0]);
6316 if( j3array[0] > IKPI )
6317 {
6318  j3array[0]-=IK2PI;
6319 }
6320 else if( j3array[0] < -IKPI )
6321 { j3array[0]+=IK2PI;
6322 }
6323 j3valid[0] = true;
6324 for(int ij3 = 0; ij3 < 1; ++ij3)
6325 {
6326 if( !j3valid[ij3] )
6327 {
6328  continue;
6329 }
6330 _ij3[0] = ij3; _ij3[1] = -1;
6331 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6332 {
6333 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6334 {
6335  j3valid[iij3]=false; _ij3[1] = iij3; break;
6336 }
6337 }
6338 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6339 {
6340 IkReal evalcond[6];
6341 IkReal x1445=IKsin(j3);
6342 IkReal x1446=IKcos(j3);
6343 IkReal x1447=((r01)*(sj8));
6344 IkReal x1448=((cj8)*(r00));
6345 IkReal x1449=((r00)*(sj8));
6346 IkReal x1450=((cj8)*(r11));
6347 IkReal x1451=((r11)*(sj8));
6348 IkReal x1452=((r10)*(sj8));
6349 IkReal x1453=((cj8)*(r10));
6350 IkReal x1454=((cj7)*(x1445));
6351 IkReal x1455=((sj7)*(x1446));
6352 IkReal x1456=((IkReal(1.00000000000000))*(x1445));
6353 IkReal x1457=((IkReal(1.00000000000000))*(x1446));
6354 IkReal x1458=((cj8)*(x1445));
6355 IkReal x1459=((IkReal(1.00000000000000))*(x1451));
6356 IkReal x1460=((sj7)*(x1445));
6357 IkReal x1461=((cj7)*(x1446));
6358 evalcond[0]=((IkReal(-1.00000000000000))+(((x1445)*(x1449)))+(((r01)*(x1458)))+(((IkReal(-1.00000000000000))*(x1452)*(x1457)))+(((IkReal(-1.00000000000000))*(x1450)*(x1457))));
6359 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1457)))+(((IkReal(-1.00000000000000))*(x1452)*(x1456)))+(((IkReal(-1.00000000000000))*(x1449)*(x1457)))+(((IkReal(-1.00000000000000))*(x1450)*(x1456))));
6360 evalcond[2]=((((x1453)*(x1461)))+(((x1447)*(x1454)))+(((r12)*(x1455)))+(((IkReal(-1.00000000000000))*(cj7)*(x1451)*(x1457)))+(((IkReal(-1.00000000000000))*(x1448)*(x1454)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1456))));
6361 evalcond[3]=((((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1457)))+(((IkReal(-1.00000000000000))*(x1455)*(x1459)))+(((x1447)*(x1460)))+(((IkReal(-1.00000000000000))*(sj7)*(x1448)*(x1456)))+(((x1453)*(x1455)))+(((r02)*(x1454))));
6362 evalcond[4]=((((IkReal(-1.00000000000000))*(x1454)*(x1459)))+(((IkReal(-1.00000000000000))*(cj7)*(x1447)*(x1457)))+(((cj5)*(sj4)))+(((x1448)*(x1461)))+(((cj4)*(sj5)))+(((r12)*(x1460)))+(((x1453)*(x1454)))+(((r02)*(x1455))));
6363 evalcond[5]=((((x1453)*(x1460)))+(((IkReal(-1.00000000000000))*(x1447)*(x1455)))+(((IkReal(-1.00000000000000))*(sj7)*(x1451)*(x1456)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1457)))+(((x1448)*(x1455)))+(((sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)))+(((IkReal(-1.00000000000000))*(r12)*(x1454))));
6364 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
6365 {
6366 continue;
6367 }
6368 }
6369 
6370 {
6371 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6372 vinfos[0].jointtype = 1;
6373 vinfos[0].foffset = j3;
6374 vinfos[0].indices[0] = _ij3[0];
6375 vinfos[0].indices[1] = _ij3[1];
6376 vinfos[0].maxsolutions = _nj3;
6377 vinfos[1].jointtype = 1;
6378 vinfos[1].foffset = j4;
6379 vinfos[1].indices[0] = _ij4[0];
6380 vinfos[1].indices[1] = _ij4[1];
6381 vinfos[1].maxsolutions = _nj4;
6382 vinfos[2].jointtype = 1;
6383 vinfos[2].foffset = j5;
6384 vinfos[2].indices[0] = _ij5[0];
6385 vinfos[2].indices[1] = _ij5[1];
6386 vinfos[2].maxsolutions = _nj5;
6387 vinfos[3].jointtype = 1;
6388 vinfos[3].foffset = j6;
6389 vinfos[3].indices[0] = _ij6[0];
6390 vinfos[3].indices[1] = _ij6[1];
6391 vinfos[3].maxsolutions = _nj6;
6392 vinfos[4].jointtype = 1;
6393 vinfos[4].foffset = j7;
6394 vinfos[4].indices[0] = _ij7[0];
6395 vinfos[4].indices[1] = _ij7[1];
6396 vinfos[4].maxsolutions = _nj7;
6397 vinfos[5].jointtype = 1;
6398 vinfos[5].foffset = j8;
6399 vinfos[5].indices[0] = _ij8[0];
6400 vinfos[5].indices[1] = _ij8[1];
6401 vinfos[5].maxsolutions = _nj8;
6402 std::vector<int> vfree(0);
6403 solutions.AddSolution(vinfos,vfree);
6404 }
6405 }
6406 }
6407 
6408 }
6409 
6410 }
6411 }
6412 }
6413 
6414 }
6415 
6416 }
6417 
6418 } else
6419 {
6420 {
6421 IkReal j3array[1], cj3array[1], sj3array[1];
6422 bool j3valid[1]={false};
6423 _nj3 = 1;
6424 if( IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst39)*(((((r10)*(sj8)))+(((cj8)*(r11))))))) < IKFAST_ATAN2_MAGTHRESH )
6425  continue;
6426 j3array[0]=IKatan2(((gconst39)*(((((IkReal(-1.00000000000000))*(r00)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)))))), ((gconst39)*(((((r10)*(sj8)))+(((cj8)*(r11)))))));
6427 sj3array[0]=IKsin(j3array[0]);
6428 cj3array[0]=IKcos(j3array[0]);
6429 if( j3array[0] > IKPI )
6430 {
6431  j3array[0]-=IK2PI;
6432 }
6433 else if( j3array[0] < -IKPI )
6434 { j3array[0]+=IK2PI;
6435 }
6436 j3valid[0] = true;
6437 for(int ij3 = 0; ij3 < 1; ++ij3)
6438 {
6439 if( !j3valid[ij3] )
6440 {
6441  continue;
6442 }
6443 _ij3[0] = ij3; _ij3[1] = -1;
6444 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6445 {
6446 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6447 {
6448  j3valid[iij3]=false; _ij3[1] = iij3; break;
6449 }
6450 }
6451 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6452 {
6453 IkReal evalcond[4];
6454 IkReal x1462=IKsin(j3);
6455 IkReal x1463=IKcos(j3);
6456 IkReal x1464=((IkReal(1.00000000000000))*(sj8));
6457 IkReal x1465=((IkReal(1.00000000000000))*(cj8));
6458 IkReal x1466=((r01)*(sj8));
6459 IkReal x1467=((cj8)*(r10));
6460 IkReal x1468=((sj7)*(x1463));
6461 IkReal x1469=((cj7)*(x1462));
6462 IkReal x1470=((r00)*(x1462));
6463 IkReal x1471=((sj7)*(x1462));
6464 IkReal x1472=((cj7)*(x1463));
6465 evalcond[0]=((IkReal(-1.00000000000000))+(((sj8)*(x1470)))+(((IkReal(-1.00000000000000))*(r10)*(x1463)*(x1464)))+(((IkReal(-1.00000000000000))*(r11)*(x1463)*(x1465)))+(((cj8)*(r01)*(x1462))));
6466 evalcond[1]=((((IkReal(-1.00000000000000))*(r01)*(x1463)*(x1465)))+(((IkReal(-1.00000000000000))*(r10)*(x1462)*(x1464)))+(((IkReal(-1.00000000000000))*(r00)*(x1463)*(x1464)))+(((IkReal(-1.00000000000000))*(r11)*(x1462)*(x1465))));
6467 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x1465)*(x1469)))+(((IkReal(-1.00000000000000))*(r11)*(x1464)*(x1472)))+(((x1467)*(x1472)))+(((x1466)*(x1469)))+(((IkReal(-1.00000000000000))*(r02)*(x1471)))+(((r12)*(x1468))));
6468 evalcond[3]=((((x1466)*(x1471)))+(((IkReal(-1.00000000000000))*(r12)*(x1472)))+(((IkReal(-1.00000000000000))*(sj7)*(x1465)*(x1470)))+(((x1467)*(x1468)))+(((IkReal(-1.00000000000000))*(r11)*(x1464)*(x1468)))+(((r02)*(x1469))));
6469 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
6470 {
6471 continue;
6472 }
6473 }
6474 
6475 {
6476 IkReal dummyeval[1];
6477 IkReal gconst42;
6478 gconst42=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
6479 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
6480 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6481 {
6482 {
6483 IkReal dummyeval[1];
6484 IkReal gconst43;
6485 gconst43=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
6486 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
6487 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6488 {
6489 continue;
6490 
6491 } else
6492 {
6493 {
6494 IkReal j4array[1], cj4array[1], sj4array[1];
6495 bool j4valid[1]={false};
6496 _nj4 = 1;
6497 IkReal x1473=((cj3)*(r01));
6498 IkReal x1474=((cj5)*(sj7));
6499 IkReal x1475=((r11)*(sj3));
6500 IkReal x1476=((r10)*(sj3));
6501 IkReal x1477=((cj3)*(r00));
6502 IkReal x1478=((r12)*(sj3));
6503 IkReal x1479=((sj5)*(sj7));
6504 IkReal x1480=((cj7)*(sj5));
6505 IkReal x1481=((cj3)*(r02)*(sj7));
6506 IkReal x1482=((IkReal(1.00000000000000))*(x1480));
6507 IkReal x1483=((cj5)*(cj7)*(cj8));
6508 IkReal x1484=((IkReal(1.00000000000000))*(cj5)*(cj7)*(sj8));
6509 if( IKabs(((gconst43)*(((((x1476)*(x1483)))+(((x1474)*(x1478)))+(((x1477)*(x1483)))+(((r21)*(sj8)*(x1480)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x1482)))+(((IkReal(-1.00000000000000))*(x1475)*(x1484)))+(((IkReal(-1.00000000000000))*(r22)*(x1479)))+(((IkReal(-1.00000000000000))*(x1473)*(x1484)))+(((cj3)*(r02)*(x1474))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((cj8)*(x1476)*(x1480)))+(((cj8)*(x1477)*(x1480)))+(((x1478)*(x1479)))+(((IkReal(-1.00000000000000))*(r21)*(x1484)))+(((r20)*(x1483)))+(((r22)*(x1474)))+(((cj3)*(r02)*(x1479)))+(((IkReal(-1.00000000000000))*(sj8)*(x1473)*(x1482)))+(((IkReal(-1.00000000000000))*(sj8)*(x1475)*(x1482))))))) < IKFAST_ATAN2_MAGTHRESH )
6510  continue;
6511 j4array[0]=IKatan2(((gconst43)*(((((x1476)*(x1483)))+(((x1474)*(x1478)))+(((x1477)*(x1483)))+(((r21)*(sj8)*(x1480)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x1482)))+(((IkReal(-1.00000000000000))*(x1475)*(x1484)))+(((IkReal(-1.00000000000000))*(r22)*(x1479)))+(((IkReal(-1.00000000000000))*(x1473)*(x1484)))+(((cj3)*(r02)*(x1474)))))), ((gconst43)*(((((cj8)*(x1476)*(x1480)))+(((cj8)*(x1477)*(x1480)))+(((x1478)*(x1479)))+(((IkReal(-1.00000000000000))*(r21)*(x1484)))+(((r20)*(x1483)))+(((r22)*(x1474)))+(((cj3)*(r02)*(x1479)))+(((IkReal(-1.00000000000000))*(sj8)*(x1473)*(x1482)))+(((IkReal(-1.00000000000000))*(sj8)*(x1475)*(x1482)))))));
6512 sj4array[0]=IKsin(j4array[0]);
6513 cj4array[0]=IKcos(j4array[0]);
6514 if( j4array[0] > IKPI )
6515 {
6516  j4array[0]-=IK2PI;
6517 }
6518 else if( j4array[0] < -IKPI )
6519 { j4array[0]+=IK2PI;
6520 }
6521 j4valid[0] = true;
6522 for(int ij4 = 0; ij4 < 1; ++ij4)
6523 {
6524 if( !j4valid[ij4] )
6525 {
6526  continue;
6527 }
6528 _ij4[0] = ij4; _ij4[1] = -1;
6529 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
6530 {
6531 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
6532 {
6533  j4valid[iij4]=false; _ij4[1] = iij4; break;
6534 }
6535 }
6536 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
6537 {
6538 IkReal evalcond[4];
6539 IkReal x1485=IKcos(j4);
6540 IkReal x1486=IKsin(j4);
6541 IkReal x1487=((IkReal(1.00000000000000))*(cj7));
6542 IkReal x1488=((cj8)*(r20));
6543 IkReal x1489=((cj3)*(r02));
6544 IkReal x1490=((IkReal(1.00000000000000))*(sj7));
6545 IkReal x1491=((sj3)*(sj7));
6546 IkReal x1492=((r21)*(sj8));
6547 IkReal x1493=((IkReal(1.00000000000000))*(cj5));
6548 IkReal x1494=((cj8)*(r10));
6549 IkReal x1495=((sj5)*(x1486));
6550 IkReal x1496=((sj5)*(x1485));
6551 IkReal x1497=((r11)*(sj3)*(sj8));
6552 IkReal x1498=((cj3)*(cj8)*(r00));
6553 IkReal x1499=((cj3)*(r01)*(sj8));
6554 IkReal x1500=((x1485)*(x1493));
6555 evalcond[0]=((((IkReal(-1.00000000000000))*(x1500)))+(((IkReal(-1.00000000000000))*(x1487)*(x1488)))+(x1495)+(((IkReal(-1.00000000000000))*(r22)*(x1490)))+(((cj7)*(x1492))));
6556 evalcond[1]=((((IkReal(-1.00000000000000))*(x1486)*(x1493)))+(((IkReal(-1.00000000000000))*(x1496)))+(((sj7)*(x1492)))+(((IkReal(-1.00000000000000))*(x1488)*(x1490)))+(((cj7)*(r22))));
6557 evalcond[2]=((((IkReal(-1.00000000000000))*(x1487)*(x1497)))+(((IkReal(-1.00000000000000))*(x1487)*(x1499)))+(((cj7)*(sj3)*(x1494)))+(((r12)*(x1491)))+(((cj5)*(x1486)))+(x1496)+(((sj7)*(x1489)))+(((cj7)*(x1498))));
6558 evalcond[3]=((((IkReal(-1.00000000000000))*(x1500)))+(((IkReal(-1.00000000000000))*(x1487)*(x1489)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1487)))+(((x1491)*(x1494)))+(((sj7)*(x1498)))+(x1495)+(((IkReal(-1.00000000000000))*(x1490)*(x1497)))+(((IkReal(-1.00000000000000))*(x1490)*(x1499))));
6559 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
6560 {
6561 continue;
6562 }
6563 }
6564 
6565 {
6566 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6567 vinfos[0].jointtype = 1;
6568 vinfos[0].foffset = j3;
6569 vinfos[0].indices[0] = _ij3[0];
6570 vinfos[0].indices[1] = _ij3[1];
6571 vinfos[0].maxsolutions = _nj3;
6572 vinfos[1].jointtype = 1;
6573 vinfos[1].foffset = j4;
6574 vinfos[1].indices[0] = _ij4[0];
6575 vinfos[1].indices[1] = _ij4[1];
6576 vinfos[1].maxsolutions = _nj4;
6577 vinfos[2].jointtype = 1;
6578 vinfos[2].foffset = j5;
6579 vinfos[2].indices[0] = _ij5[0];
6580 vinfos[2].indices[1] = _ij5[1];
6581 vinfos[2].maxsolutions = _nj5;
6582 vinfos[3].jointtype = 1;
6583 vinfos[3].foffset = j6;
6584 vinfos[3].indices[0] = _ij6[0];
6585 vinfos[3].indices[1] = _ij6[1];
6586 vinfos[3].maxsolutions = _nj6;
6587 vinfos[4].jointtype = 1;
6588 vinfos[4].foffset = j7;
6589 vinfos[4].indices[0] = _ij7[0];
6590 vinfos[4].indices[1] = _ij7[1];
6591 vinfos[4].maxsolutions = _nj7;
6592 vinfos[5].jointtype = 1;
6593 vinfos[5].foffset = j8;
6594 vinfos[5].indices[0] = _ij8[0];
6595 vinfos[5].indices[1] = _ij8[1];
6596 vinfos[5].maxsolutions = _nj8;
6597 std::vector<int> vfree(0);
6598 solutions.AddSolution(vinfos,vfree);
6599 }
6600 }
6601 }
6602 
6603 }
6604 
6605 }
6606 
6607 } else
6608 {
6609 {
6610 IkReal j4array[1], cj4array[1], sj4array[1];
6611 bool j4valid[1]={false};
6612 _nj4 = 1;
6613 IkReal x1501=((cj7)*(sj5));
6614 IkReal x1502=((r21)*(sj8));
6615 IkReal x1503=((cj5)*(cj7));
6616 IkReal x1504=((cj8)*(r20));
6617 IkReal x1505=((sj5)*(sj7));
6618 IkReal x1506=((IkReal(1.00000000000000))*(cj5)*(sj7));
6619 if( IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(x1504)*(x1506)))+(((x1501)*(x1504)))+(((cj5)*(sj7)*(x1502)))+(((r22)*(x1503)))+(((r22)*(x1505)))+(((IkReal(-1.00000000000000))*(x1501)*(x1502))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(x1504)*(x1505)))+(((IkReal(-1.00000000000000))*(r22)*(x1506)))+(((IkReal(-1.00000000000000))*(x1503)*(x1504)))+(((r22)*(x1501)))+(((x1502)*(x1503)))+(((x1502)*(x1505))))))) < IKFAST_ATAN2_MAGTHRESH )
6620  continue;
6621 j4array[0]=IKatan2(((gconst42)*(((((IkReal(-1.00000000000000))*(x1504)*(x1506)))+(((x1501)*(x1504)))+(((cj5)*(sj7)*(x1502)))+(((r22)*(x1503)))+(((r22)*(x1505)))+(((IkReal(-1.00000000000000))*(x1501)*(x1502)))))), ((gconst42)*(((((IkReal(-1.00000000000000))*(x1504)*(x1505)))+(((IkReal(-1.00000000000000))*(r22)*(x1506)))+(((IkReal(-1.00000000000000))*(x1503)*(x1504)))+(((r22)*(x1501)))+(((x1502)*(x1503)))+(((x1502)*(x1505)))))));
6622 sj4array[0]=IKsin(j4array[0]);
6623 cj4array[0]=IKcos(j4array[0]);
6624 if( j4array[0] > IKPI )
6625 {
6626  j4array[0]-=IK2PI;
6627 }
6628 else if( j4array[0] < -IKPI )
6629 { j4array[0]+=IK2PI;
6630 }
6631 j4valid[0] = true;
6632 for(int ij4 = 0; ij4 < 1; ++ij4)
6633 {
6634 if( !j4valid[ij4] )
6635 {
6636  continue;
6637 }
6638 _ij4[0] = ij4; _ij4[1] = -1;
6639 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
6640 {
6641 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
6642 {
6643  j4valid[iij4]=false; _ij4[1] = iij4; break;
6644 }
6645 }
6646 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
6647 {
6648 IkReal evalcond[4];
6649 IkReal x1507=IKcos(j4);
6650 IkReal x1508=IKsin(j4);
6651 IkReal x1509=((IkReal(1.00000000000000))*(cj7));
6652 IkReal x1510=((cj8)*(r20));
6653 IkReal x1511=((cj3)*(r02));
6654 IkReal x1512=((IkReal(1.00000000000000))*(sj7));
6655 IkReal x1513=((sj3)*(sj7));
6656 IkReal x1514=((r21)*(sj8));
6657 IkReal x1515=((IkReal(1.00000000000000))*(cj5));
6658 IkReal x1516=((cj8)*(r10));
6659 IkReal x1517=((sj5)*(x1508));
6660 IkReal x1518=((sj5)*(x1507));
6661 IkReal x1519=((r11)*(sj3)*(sj8));
6662 IkReal x1520=((cj3)*(cj8)*(r00));
6663 IkReal x1521=((cj3)*(r01)*(sj8));
6664 IkReal x1522=((x1507)*(x1515));
6665 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x1512)))+(((IkReal(-1.00000000000000))*(x1522)))+(x1517)+(((IkReal(-1.00000000000000))*(x1509)*(x1510)))+(((cj7)*(x1514))));
6666 evalcond[1]=((((IkReal(-1.00000000000000))*(x1518)))+(((IkReal(-1.00000000000000))*(x1510)*(x1512)))+(((sj7)*(x1514)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x1508)*(x1515))));
6667 evalcond[2]=((((cj7)*(x1520)))+(((r12)*(x1513)))+(((cj7)*(sj3)*(x1516)))+(x1518)+(((cj5)*(x1508)))+(((sj7)*(x1511)))+(((IkReal(-1.00000000000000))*(x1509)*(x1519)))+(((IkReal(-1.00000000000000))*(x1509)*(x1521))));
6668 evalcond[3]=((((x1513)*(x1516)))+(((IkReal(-1.00000000000000))*(x1522)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1509)))+(x1517)+(((IkReal(-1.00000000000000))*(x1512)*(x1521)))+(((sj7)*(x1520)))+(((IkReal(-1.00000000000000))*(x1512)*(x1519)))+(((IkReal(-1.00000000000000))*(x1509)*(x1511))));
6669 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
6670 {
6671 continue;
6672 }
6673 }
6674 
6675 {
6676 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6677 vinfos[0].jointtype = 1;
6678 vinfos[0].foffset = j3;
6679 vinfos[0].indices[0] = _ij3[0];
6680 vinfos[0].indices[1] = _ij3[1];
6681 vinfos[0].maxsolutions = _nj3;
6682 vinfos[1].jointtype = 1;
6683 vinfos[1].foffset = j4;
6684 vinfos[1].indices[0] = _ij4[0];
6685 vinfos[1].indices[1] = _ij4[1];
6686 vinfos[1].maxsolutions = _nj4;
6687 vinfos[2].jointtype = 1;
6688 vinfos[2].foffset = j5;
6689 vinfos[2].indices[0] = _ij5[0];
6690 vinfos[2].indices[1] = _ij5[1];
6691 vinfos[2].maxsolutions = _nj5;
6692 vinfos[3].jointtype = 1;
6693 vinfos[3].foffset = j6;
6694 vinfos[3].indices[0] = _ij6[0];
6695 vinfos[3].indices[1] = _ij6[1];
6696 vinfos[3].maxsolutions = _nj6;
6697 vinfos[4].jointtype = 1;
6698 vinfos[4].foffset = j7;
6699 vinfos[4].indices[0] = _ij7[0];
6700 vinfos[4].indices[1] = _ij7[1];
6701 vinfos[4].maxsolutions = _nj7;
6702 vinfos[5].jointtype = 1;
6703 vinfos[5].foffset = j8;
6704 vinfos[5].indices[0] = _ij8[0];
6705 vinfos[5].indices[1] = _ij8[1];
6706 vinfos[5].maxsolutions = _nj8;
6707 std::vector<int> vfree(0);
6708 solutions.AddSolution(vinfos,vfree);
6709 }
6710 }
6711 }
6712 
6713 }
6714 
6715 }
6716 }
6717 }
6718 
6719 }
6720 
6721 }
6722 
6723 } else
6724 {
6725 if( 1 )
6726 {
6727 continue;
6728 
6729 } else
6730 {
6731 }
6732 }
6733 }
6734 }
6735 }
6736 }
6737 
6738 } else
6739 {
6740 {
6741 IkReal j3array[1], cj3array[1], sj3array[1];
6742 bool j3valid[1]={false};
6743 _nj3 = 1;
6744 IkReal x1523=((cj6)*(cj7));
6745 IkReal x1524=((IkReal(1.00000000000000))*(sj8));
6746 IkReal x1525=((cj6)*(sj7));
6747 if( IKabs(((gconst2)*(((((r12)*(x1525)))+(((cj8)*(r10)*(x1523)))+(((IkReal(-1.00000000000000))*(r11)*(x1523)*(x1524))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((cj8)*(r00)*(x1523)))+(((IkReal(-1.00000000000000))*(r01)*(x1523)*(x1524)))+(((r02)*(x1525))))))) < IKFAST_ATAN2_MAGTHRESH )
6748  continue;
6749 j3array[0]=IKatan2(((gconst2)*(((((r12)*(x1525)))+(((cj8)*(r10)*(x1523)))+(((IkReal(-1.00000000000000))*(r11)*(x1523)*(x1524)))))), ((gconst2)*(((((cj8)*(r00)*(x1523)))+(((IkReal(-1.00000000000000))*(r01)*(x1523)*(x1524)))+(((r02)*(x1525)))))));
6750 sj3array[0]=IKsin(j3array[0]);
6751 cj3array[0]=IKcos(j3array[0]);
6752 if( j3array[0] > IKPI )
6753 {
6754  j3array[0]-=IK2PI;
6755 }
6756 else if( j3array[0] < -IKPI )
6757 { j3array[0]+=IK2PI;
6758 }
6759 j3valid[0] = true;
6760 for(int ij3 = 0; ij3 < 1; ++ij3)
6761 {
6762 if( !j3valid[ij3] )
6763 {
6764  continue;
6765 }
6766 _ij3[0] = ij3; _ij3[1] = -1;
6767 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
6768 {
6769 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
6770 {
6771  j3valid[iij3]=false; _ij3[1] = iij3; break;
6772 }
6773 }
6774 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
6775 {
6776 IkReal evalcond[3];
6777 IkReal x1526=IKsin(j3);
6778 IkReal x1527=IKcos(j3);
6779 IkReal x1528=((IkReal(1.00000000000000))*(r11));
6780 IkReal x1529=((r01)*(sj8));
6781 IkReal x1530=((cj8)*(r10));
6782 IkReal x1531=((IkReal(1.00000000000000))*(sj7));
6783 IkReal x1532=((sj7)*(x1527));
6784 IkReal x1533=((cj7)*(x1526));
6785 IkReal x1534=((r00)*(x1526));
6786 IkReal x1535=((cj7)*(x1527));
6787 evalcond[0]=((cj6)+(((cj8)*(r01)*(x1526)))+(((sj8)*(x1534)))+(((IkReal(-1.00000000000000))*(cj8)*(x1527)*(x1528)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x1527))));
6788 evalcond[1]=((((r12)*(x1532)))+(((x1530)*(x1535)))+(((IkReal(-1.00000000000000))*(sj8)*(x1528)*(x1535)))+(((x1529)*(x1533)))+(((IkReal(-1.00000000000000))*(r02)*(x1526)*(x1531)))+(((IkReal(-1.00000000000000))*(cj8)*(r00)*(x1533))));
6789 evalcond[2]=((((sj7)*(x1526)*(x1529)))+(sj6)+(((IkReal(-1.00000000000000))*(cj8)*(x1531)*(x1534)))+(((x1530)*(x1532)))+(((IkReal(-1.00000000000000))*(sj8)*(x1528)*(x1532)))+(((r02)*(x1533)))+(((IkReal(-1.00000000000000))*(r12)*(x1535))));
6790 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
6791 {
6792 continue;
6793 }
6794 }
6795 
6796 {
6797 IkReal dummyeval[1];
6798 IkReal gconst6;
6799 gconst6=IKsign(((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5))))));
6800 dummyeval[0]=((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5)))));
6801 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6802 {
6803 {
6804 IkReal dummyeval[1];
6805 IkReal gconst7;
6806 gconst7=IKsign(((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5))))));
6807 dummyeval[0]=((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5)))));
6808 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6809 {
6810 {
6811 IkReal evalcond[9];
6812 IkReal x1536=((IkReal(1.00000000000000))*(sj7));
6813 IkReal x1537=((IkReal(1.00000000000000))*(cj3));
6814 IkReal x1538=((cj7)*(r02));
6815 IkReal x1539=((cj8)*(r00));
6816 IkReal x1540=((cj3)*(sj7));
6817 IkReal x1541=((cj8)*(npx));
6818 IkReal x1542=((r01)*(sj3));
6819 IkReal x1543=((cj7)*(sj8));
6820 IkReal x1544=((r11)*(sj8));
6821 IkReal x1545=((IkReal(1.00000000000000))*(cj7));
6822 IkReal x1546=((sj7)*(sj8));
6823 IkReal x1547=((cj8)*(r10));
6824 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
6825 evalcond[1]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(sj5))));
6826 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x1536)))+(((npy)*(x1543)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(x1541)*(x1545))));
6827 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj8)*(x1537)))+(((cj8)*(x1542)))+(((r00)*(sj3)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r11)*(x1537))));
6828 evalcond[4]=((((r21)*(x1546)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x1536)))+(((cj7)*(r22))));
6829 evalcond[5]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x1546)))+(((IkReal(-1.00000000000000))*(x1536)*(x1541)))+(((cj7)*(npz))));
6830 evalcond[6]=((((r12)*(x1540)))+(((IkReal(-1.00000000000000))*(r11)*(x1537)*(x1543)))+(((cj3)*(cj7)*(x1547)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x1536)))+(((x1542)*(x1543)))+(((IkReal(-1.00000000000000))*(sj3)*(x1539)*(x1545))));
6831 evalcond[7]=((IkReal(1.00000000000000))+(((sj3)*(x1538)))+(((IkReal(-1.00000000000000))*(cj3)*(x1536)*(x1544)))+(((IkReal(-1.00000000000000))*(sj3)*(x1536)*(x1539)))+(((x1540)*(x1547)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1537)))+(((x1542)*(x1546))));
6832 evalcond[8]=((((x1539)*(x1540)))+(((IkReal(-1.00000000000000))*(x1537)*(x1538)))+(((IkReal(-1.00000000000000))*(sj3)*(x1536)*(x1544)))+(((sj3)*(sj7)*(x1547)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1545)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x1536))));
6833 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
6834 {
6835 {
6836 IkReal dummyeval[1];
6837 IkReal gconst8;
6838 gconst8=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
6839 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
6840 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6841 {
6842 {
6843 IkReal dummyeval[1];
6844 IkReal gconst9;
6845 gconst9=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
6846 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
6847 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
6848 {
6849 continue;
6850 
6851 } else
6852 {
6853 {
6854 IkReal j4array[1], cj4array[1], sj4array[1];
6855 bool j4valid[1]={false};
6856 _nj4 = 1;
6857 IkReal x1548=((cj8)*(sj5));
6858 IkReal x1549=((cj3)*(r01));
6859 IkReal x1550=((IkReal(1.00000000000000))*(cj5));
6860 IkReal x1551=((sj5)*(sj8));
6861 IkReal x1552=((r10)*(sj3));
6862 IkReal x1553=((r11)*(sj3));
6863 IkReal x1554=((cj3)*(r00)*(sj8));
6864 if( IKabs(((gconst9)*(((((x1551)*(x1552)))+(((cj3)*(r00)*(x1551)))+(((cj5)*(r20)*(sj8)))+(((x1548)*(x1553)))+(((x1548)*(x1549)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((((IkReal(-1.00000000000000))*(cj8)*(x1550)*(x1553)))+(((r21)*(x1548)))+(((IkReal(-1.00000000000000))*(x1550)*(x1554)))+(((IkReal(-1.00000000000000))*(cj8)*(x1549)*(x1550)))+(((r20)*(x1551)))+(((IkReal(-1.00000000000000))*(sj8)*(x1550)*(x1552))))))) < IKFAST_ATAN2_MAGTHRESH )
6865  continue;
6866 j4array[0]=IKatan2(((gconst9)*(((((x1551)*(x1552)))+(((cj3)*(r00)*(x1551)))+(((cj5)*(r20)*(sj8)))+(((x1548)*(x1553)))+(((x1548)*(x1549)))+(((cj5)*(cj8)*(r21)))))), ((gconst9)*(((((IkReal(-1.00000000000000))*(cj8)*(x1550)*(x1553)))+(((r21)*(x1548)))+(((IkReal(-1.00000000000000))*(x1550)*(x1554)))+(((IkReal(-1.00000000000000))*(cj8)*(x1549)*(x1550)))+(((r20)*(x1551)))+(((IkReal(-1.00000000000000))*(sj8)*(x1550)*(x1552)))))));
6867 sj4array[0]=IKsin(j4array[0]);
6868 cj4array[0]=IKcos(j4array[0]);
6869 if( j4array[0] > IKPI )
6870 {
6871  j4array[0]-=IK2PI;
6872 }
6873 else if( j4array[0] < -IKPI )
6874 { j4array[0]+=IK2PI;
6875 }
6876 j4valid[0] = true;
6877 for(int ij4 = 0; ij4 < 1; ++ij4)
6878 {
6879 if( !j4valid[ij4] )
6880 {
6881  continue;
6882 }
6883 _ij4[0] = ij4; _ij4[1] = -1;
6884 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
6885 {
6886 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
6887 {
6888  j4valid[iij4]=false; _ij4[1] = iij4; break;
6889 }
6890 }
6891 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
6892 {
6893 IkReal evalcond[4];
6894 IkReal x1555=IKsin(j4);
6895 IkReal x1556=IKcos(j4);
6896 IkReal x1557=((IkReal(1.00000000000000))*(cj8));
6897 IkReal x1558=((cj3)*(r01));
6898 IkReal x1559=((cj3)*(r00));
6899 IkReal x1560=((cj7)*(cj8));
6900 IkReal x1561=((IkReal(1.00000000000000))*(cj5));
6901 IkReal x1562=((IkReal(1.00000000000000))*(sj8));
6902 IkReal x1563=((r11)*(sj3));
6903 IkReal x1564=((r10)*(sj3));
6904 IkReal x1565=((sj5)*(x1555));
6905 IkReal x1566=((sj5)*(x1556));
6906 IkReal x1567=((x1556)*(x1561));
6907 evalcond[0]=((((IkReal(-1.00000000000000))*(x1555)*(x1561)))+(((cj8)*(r21)))+(((r20)*(sj8)))+(((IkReal(-1.00000000000000))*(x1566))));
6908 evalcond[1]=((x1565)+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x1567)))+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x1557))));
6909 evalcond[2]=((((IkReal(-1.00000000000000))*(x1559)*(x1562)))+(((IkReal(-1.00000000000000))*(x1557)*(x1563)))+(((IkReal(-1.00000000000000))*(x1562)*(x1564)))+(x1565)+(((IkReal(-1.00000000000000))*(x1557)*(x1558)))+(((IkReal(-1.00000000000000))*(x1567))));
6910 evalcond[3]=((((x1560)*(x1564)))+(((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x1558)*(x1562)))+(x1566)+(((cj3)*(r02)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x1562)*(x1563)))+(((x1559)*(x1560)))+(((cj5)*(x1555))));
6911 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
6912 {
6913 continue;
6914 }
6915 }
6916 
6917 {
6918 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6919 vinfos[0].jointtype = 1;
6920 vinfos[0].foffset = j3;
6921 vinfos[0].indices[0] = _ij3[0];
6922 vinfos[0].indices[1] = _ij3[1];
6923 vinfos[0].maxsolutions = _nj3;
6924 vinfos[1].jointtype = 1;
6925 vinfos[1].foffset = j4;
6926 vinfos[1].indices[0] = _ij4[0];
6927 vinfos[1].indices[1] = _ij4[1];
6928 vinfos[1].maxsolutions = _nj4;
6929 vinfos[2].jointtype = 1;
6930 vinfos[2].foffset = j5;
6931 vinfos[2].indices[0] = _ij5[0];
6932 vinfos[2].indices[1] = _ij5[1];
6933 vinfos[2].maxsolutions = _nj5;
6934 vinfos[3].jointtype = 1;
6935 vinfos[3].foffset = j6;
6936 vinfos[3].indices[0] = _ij6[0];
6937 vinfos[3].indices[1] = _ij6[1];
6938 vinfos[3].maxsolutions = _nj6;
6939 vinfos[4].jointtype = 1;
6940 vinfos[4].foffset = j7;
6941 vinfos[4].indices[0] = _ij7[0];
6942 vinfos[4].indices[1] = _ij7[1];
6943 vinfos[4].maxsolutions = _nj7;
6944 vinfos[5].jointtype = 1;
6945 vinfos[5].foffset = j8;
6946 vinfos[5].indices[0] = _ij8[0];
6947 vinfos[5].indices[1] = _ij8[1];
6948 vinfos[5].maxsolutions = _nj8;
6949 std::vector<int> vfree(0);
6950 solutions.AddSolution(vinfos,vfree);
6951 }
6952 }
6953 }
6954 
6955 }
6956 
6957 }
6958 
6959 } else
6960 {
6961 {
6962 IkReal j4array[1], cj4array[1], sj4array[1];
6963 bool j4valid[1]={false};
6964 _nj4 = 1;
6965 IkReal x1568=((sj5)*(sj8));
6966 IkReal x1569=((IkReal(1.00000000000000))*(cj7));
6967 IkReal x1570=((cj8)*(sj5));
6968 IkReal x1571=((r22)*(sj7));
6969 IkReal x1572=((cj5)*(cj8));
6970 IkReal x1573=((cj5)*(sj8));
6971 if( IKabs(((gconst8)*(((((r20)*(x1573)))+(((cj7)*(r20)*(x1570)))+(((IkReal(-1.00000000000000))*(r21)*(x1568)*(x1569)))+(((r21)*(x1572)))+(((sj5)*(x1571))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((((r20)*(x1568)))+(((cj7)*(r21)*(x1573)))+(((IkReal(-1.00000000000000))*(r20)*(x1569)*(x1572)))+(((r21)*(x1570)))+(((IkReal(-1.00000000000000))*(cj5)*(x1571))))))) < IKFAST_ATAN2_MAGTHRESH )
6972  continue;
6973 j4array[0]=IKatan2(((gconst8)*(((((r20)*(x1573)))+(((cj7)*(r20)*(x1570)))+(((IkReal(-1.00000000000000))*(r21)*(x1568)*(x1569)))+(((r21)*(x1572)))+(((sj5)*(x1571)))))), ((gconst8)*(((((r20)*(x1568)))+(((cj7)*(r21)*(x1573)))+(((IkReal(-1.00000000000000))*(r20)*(x1569)*(x1572)))+(((r21)*(x1570)))+(((IkReal(-1.00000000000000))*(cj5)*(x1571)))))));
6974 sj4array[0]=IKsin(j4array[0]);
6975 cj4array[0]=IKcos(j4array[0]);
6976 if( j4array[0] > IKPI )
6977 {
6978  j4array[0]-=IK2PI;
6979 }
6980 else if( j4array[0] < -IKPI )
6981 { j4array[0]+=IK2PI;
6982 }
6983 j4valid[0] = true;
6984 for(int ij4 = 0; ij4 < 1; ++ij4)
6985 {
6986 if( !j4valid[ij4] )
6987 {
6988  continue;
6989 }
6990 _ij4[0] = ij4; _ij4[1] = -1;
6991 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
6992 {
6993 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
6994 {
6995  j4valid[iij4]=false; _ij4[1] = iij4; break;
6996 }
6997 }
6998 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
6999 {
7000 IkReal evalcond[4];
7001 IkReal x1574=IKsin(j4);
7002 IkReal x1575=IKcos(j4);
7003 IkReal x1576=((IkReal(1.00000000000000))*(cj8));
7004 IkReal x1577=((cj3)*(r01));
7005 IkReal x1578=((cj3)*(r00));
7006 IkReal x1579=((cj7)*(cj8));
7007 IkReal x1580=((IkReal(1.00000000000000))*(cj5));
7008 IkReal x1581=((IkReal(1.00000000000000))*(sj8));
7009 IkReal x1582=((r11)*(sj3));
7010 IkReal x1583=((r10)*(sj3));
7011 IkReal x1584=((sj5)*(x1574));
7012 IkReal x1585=((sj5)*(x1575));
7013 IkReal x1586=((x1575)*(x1580));
7014 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x1574)*(x1580)))+(((IkReal(-1.00000000000000))*(x1585)))+(((r20)*(sj8))));
7015 evalcond[1]=((((IkReal(-1.00000000000000))*(x1586)))+(x1584)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x1576)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
7016 evalcond[2]=((((IkReal(-1.00000000000000))*(x1586)))+(((IkReal(-1.00000000000000))*(x1576)*(x1577)))+(((IkReal(-1.00000000000000))*(x1578)*(x1581)))+(x1584)+(((IkReal(-1.00000000000000))*(x1581)*(x1583)))+(((IkReal(-1.00000000000000))*(x1576)*(x1582))));
7017 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((cj5)*(x1574)))+(x1585)+(((IkReal(-1.00000000000000))*(cj7)*(x1577)*(x1581)))+(((cj3)*(r02)*(sj7)))+(((x1579)*(x1583)))+(((x1578)*(x1579)))+(((IkReal(-1.00000000000000))*(cj7)*(x1581)*(x1582))));
7018 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
7019 {
7020 continue;
7021 }
7022 }
7023 
7024 {
7025 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7026 vinfos[0].jointtype = 1;
7027 vinfos[0].foffset = j3;
7028 vinfos[0].indices[0] = _ij3[0];
7029 vinfos[0].indices[1] = _ij3[1];
7030 vinfos[0].maxsolutions = _nj3;
7031 vinfos[1].jointtype = 1;
7032 vinfos[1].foffset = j4;
7033 vinfos[1].indices[0] = _ij4[0];
7034 vinfos[1].indices[1] = _ij4[1];
7035 vinfos[1].maxsolutions = _nj4;
7036 vinfos[2].jointtype = 1;
7037 vinfos[2].foffset = j5;
7038 vinfos[2].indices[0] = _ij5[0];
7039 vinfos[2].indices[1] = _ij5[1];
7040 vinfos[2].maxsolutions = _nj5;
7041 vinfos[3].jointtype = 1;
7042 vinfos[3].foffset = j6;
7043 vinfos[3].indices[0] = _ij6[0];
7044 vinfos[3].indices[1] = _ij6[1];
7045 vinfos[3].maxsolutions = _nj6;
7046 vinfos[4].jointtype = 1;
7047 vinfos[4].foffset = j7;
7048 vinfos[4].indices[0] = _ij7[0];
7049 vinfos[4].indices[1] = _ij7[1];
7050 vinfos[4].maxsolutions = _nj7;
7051 vinfos[5].jointtype = 1;
7052 vinfos[5].foffset = j8;
7053 vinfos[5].indices[0] = _ij8[0];
7054 vinfos[5].indices[1] = _ij8[1];
7055 vinfos[5].maxsolutions = _nj8;
7056 std::vector<int> vfree(0);
7057 solutions.AddSolution(vinfos,vfree);
7058 }
7059 }
7060 }
7061 
7062 }
7063 
7064 }
7065 
7066 } else
7067 {
7068 IkReal x1587=((IkReal(1.00000000000000))*(sj7));
7069 IkReal x1588=((IkReal(1.00000000000000))*(cj3));
7070 IkReal x1589=((cj7)*(r02));
7071 IkReal x1590=((cj8)*(r00));
7072 IkReal x1591=((cj3)*(sj7));
7073 IkReal x1592=((cj8)*(npx));
7074 IkReal x1593=((r01)*(sj3));
7075 IkReal x1594=((cj7)*(sj8));
7076 IkReal x1595=((r11)*(sj8));
7077 IkReal x1596=((IkReal(1.00000000000000))*(cj7));
7078 IkReal x1597=((sj7)*(sj8));
7079 IkReal x1598=((cj8)*(r10));
7080 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
7081 evalcond[1]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(sj5))));
7082 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(x1592)*(x1596)))+(((IkReal(0.0900000000000000))*(cj7)))+(((npy)*(x1594)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x1587))));
7083 evalcond[3]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x1588)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x1588)))+(((cj8)*(x1593)))+(((r00)*(sj3)*(sj8))));
7084 evalcond[4]=((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x1587)))+(((r21)*(x1597)))+(((cj7)*(r22))));
7085 evalcond[5]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x1597)))+(((cj7)*(npz)))+(((IkReal(-1.00000000000000))*(x1587)*(x1592))));
7086 evalcond[6]=((((x1593)*(x1594)))+(((r12)*(x1591)))+(((IkReal(-1.00000000000000))*(r11)*(x1588)*(x1594)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x1587)))+(((cj3)*(cj7)*(x1598)))+(((IkReal(-1.00000000000000))*(sj3)*(x1590)*(x1596))));
7087 evalcond[7]=((IkReal(-1.00000000000000))+(((sj3)*(x1589)))+(((x1593)*(x1597)))+(((IkReal(-1.00000000000000))*(cj3)*(x1587)*(x1595)))+(((x1591)*(x1598)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1588)))+(((IkReal(-1.00000000000000))*(sj3)*(x1587)*(x1590))));
7088 evalcond[8]=((((x1590)*(x1591)))+(((sj3)*(sj7)*(x1598)))+(((IkReal(-1.00000000000000))*(x1588)*(x1589)))+(((IkReal(-1.00000000000000))*(sj3)*(x1587)*(x1595)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1596)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x1587))));
7089 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
7090 {
7091 {
7092 IkReal dummyeval[1];
7093 IkReal gconst10;
7094 gconst10=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
7095 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
7096 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
7097 {
7098 {
7099 IkReal dummyeval[1];
7100 IkReal gconst11;
7101 gconst11=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
7102 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
7103 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
7104 {
7105 continue;
7106 
7107 } else
7108 {
7109 {
7110 IkReal j4array[1], cj4array[1], sj4array[1];
7111 bool j4valid[1]={false};
7112 _nj4 = 1;
7113 IkReal x1599=((IkReal(1.00000000000000))*(sj5));
7114 IkReal x1600=((r20)*(sj8));
7115 IkReal x1601=((IkReal(1.00000000000000))*(cj5));
7116 IkReal x1602=((cj8)*(r21));
7117 IkReal x1603=((cj8)*(r11)*(sj3));
7118 IkReal x1604=((cj3)*(cj8)*(r01));
7119 IkReal x1605=((cj3)*(r00)*(sj8));
7120 IkReal x1606=((r10)*(sj3)*(sj8));
7121 if( IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(x1601)*(x1602)))+(((IkReal(-1.00000000000000))*(x1600)*(x1601)))+(((IkReal(-1.00000000000000))*(x1599)*(x1603)))+(((IkReal(-1.00000000000000))*(x1599)*(x1605)))+(((IkReal(-1.00000000000000))*(x1599)*(x1604)))+(((IkReal(-1.00000000000000))*(x1599)*(x1606))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((cj5)*(x1603)))+(((cj5)*(x1604)))+(((cj5)*(x1605)))+(((cj5)*(x1606)))+(((IkReal(-1.00000000000000))*(x1599)*(x1600)))+(((IkReal(-1.00000000000000))*(x1599)*(x1602))))))) < IKFAST_ATAN2_MAGTHRESH )
7122  continue;
7123 j4array[0]=IKatan2(((gconst11)*(((((IkReal(-1.00000000000000))*(x1601)*(x1602)))+(((IkReal(-1.00000000000000))*(x1600)*(x1601)))+(((IkReal(-1.00000000000000))*(x1599)*(x1603)))+(((IkReal(-1.00000000000000))*(x1599)*(x1605)))+(((IkReal(-1.00000000000000))*(x1599)*(x1604)))+(((IkReal(-1.00000000000000))*(x1599)*(x1606)))))), ((gconst11)*(((((cj5)*(x1603)))+(((cj5)*(x1604)))+(((cj5)*(x1605)))+(((cj5)*(x1606)))+(((IkReal(-1.00000000000000))*(x1599)*(x1600)))+(((IkReal(-1.00000000000000))*(x1599)*(x1602)))))));
7124 sj4array[0]=IKsin(j4array[0]);
7125 cj4array[0]=IKcos(j4array[0]);
7126 if( j4array[0] > IKPI )
7127 {
7128  j4array[0]-=IK2PI;
7129 }
7130 else if( j4array[0] < -IKPI )
7131 { j4array[0]+=IK2PI;
7132 }
7133 j4valid[0] = true;
7134 for(int ij4 = 0; ij4 < 1; ++ij4)
7135 {
7136 if( !j4valid[ij4] )
7137 {
7138  continue;
7139 }
7140 _ij4[0] = ij4; _ij4[1] = -1;
7141 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
7142 {
7143 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
7144 {
7145  j4valid[iij4]=false; _ij4[1] = iij4; break;
7146 }
7147 }
7148 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
7149 {
7150 IkReal evalcond[4];
7151 IkReal x1607=IKsin(j4);
7152 IkReal x1608=IKcos(j4);
7153 IkReal x1609=((IkReal(1.00000000000000))*(cj8));
7154 IkReal x1610=((cj3)*(r01));
7155 IkReal x1611=((cj3)*(r00));
7156 IkReal x1612=((cj7)*(cj8));
7157 IkReal x1613=((r11)*(sj3));
7158 IkReal x1614=((IkReal(1.00000000000000))*(sj8));
7159 IkReal x1615=((r10)*(sj3));
7160 IkReal x1616=((sj5)*(x1608));
7161 IkReal x1617=((cj5)*(x1607));
7162 IkReal x1618=((cj5)*(x1608));
7163 IkReal x1619=((sj5)*(x1607));
7164 IkReal x1620=((x1616)+(x1617));
7165 evalcond[0]=((x1620)+(((cj8)*(r21)))+(((r20)*(sj8))));
7166 evalcond[1]=((((IkReal(-1.00000000000000))*(x1618)))+(x1619)+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x1609)))+(((cj7)*(r21)*(sj8))));
7167 evalcond[2]=((((IkReal(-1.00000000000000))*(x1619)))+(((IkReal(-1.00000000000000))*(x1611)*(x1614)))+(x1618)+(((IkReal(-1.00000000000000))*(x1609)*(x1610)))+(((IkReal(-1.00000000000000))*(x1609)*(x1613)))+(((IkReal(-1.00000000000000))*(x1614)*(x1615))));
7168 evalcond[3]=((((r12)*(sj3)*(sj7)))+(x1620)+(((IkReal(-1.00000000000000))*(cj7)*(x1610)*(x1614)))+(((IkReal(-1.00000000000000))*(cj7)*(x1613)*(x1614)))+(((cj3)*(r02)*(sj7)))+(((x1612)*(x1615)))+(((x1611)*(x1612))));
7169 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
7170 {
7171 continue;
7172 }
7173 }
7174 
7175 {
7176 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7177 vinfos[0].jointtype = 1;
7178 vinfos[0].foffset = j3;
7179 vinfos[0].indices[0] = _ij3[0];
7180 vinfos[0].indices[1] = _ij3[1];
7181 vinfos[0].maxsolutions = _nj3;
7182 vinfos[1].jointtype = 1;
7183 vinfos[1].foffset = j4;
7184 vinfos[1].indices[0] = _ij4[0];
7185 vinfos[1].indices[1] = _ij4[1];
7186 vinfos[1].maxsolutions = _nj4;
7187 vinfos[2].jointtype = 1;
7188 vinfos[2].foffset = j5;
7189 vinfos[2].indices[0] = _ij5[0];
7190 vinfos[2].indices[1] = _ij5[1];
7191 vinfos[2].maxsolutions = _nj5;
7192 vinfos[3].jointtype = 1;
7193 vinfos[3].foffset = j6;
7194 vinfos[3].indices[0] = _ij6[0];
7195 vinfos[3].indices[1] = _ij6[1];
7196 vinfos[3].maxsolutions = _nj6;
7197 vinfos[4].jointtype = 1;
7198 vinfos[4].foffset = j7;
7199 vinfos[4].indices[0] = _ij7[0];
7200 vinfos[4].indices[1] = _ij7[1];
7201 vinfos[4].maxsolutions = _nj7;
7202 vinfos[5].jointtype = 1;
7203 vinfos[5].foffset = j8;
7204 vinfos[5].indices[0] = _ij8[0];
7205 vinfos[5].indices[1] = _ij8[1];
7206 vinfos[5].maxsolutions = _nj8;
7207 std::vector<int> vfree(0);
7208 solutions.AddSolution(vinfos,vfree);
7209 }
7210 }
7211 }
7212 
7213 }
7214 
7215 }
7216 
7217 } else
7218 {
7219 {
7220 IkReal j4array[1], cj4array[1], sj4array[1];
7221 bool j4valid[1]={false};
7222 _nj4 = 1;
7223 IkReal x1621=((r20)*(sj5));
7224 IkReal x1622=((r22)*(sj7));
7225 IkReal x1623=((cj8)*(r21));
7226 IkReal x1624=((cj7)*(cj8));
7227 IkReal x1625=((cj5)*(r20));
7228 IkReal x1626=((cj7)*(r21)*(sj8));
7229 if( IKabs(((gconst10)*(((((sj5)*(x1626)))+(((cj5)*(x1623)))+(((IkReal(-1.00000000000000))*(x1621)*(x1624)))+(((sj8)*(x1625)))+(((IkReal(-1.00000000000000))*(sj5)*(x1622))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((sj5)*(x1623)))+(((IkReal(-1.00000000000000))*(cj5)*(x1626)))+(((cj5)*(x1622)))+(((sj8)*(x1621)))+(((x1624)*(x1625))))))) < IKFAST_ATAN2_MAGTHRESH )
7230  continue;
7231 j4array[0]=IKatan2(((gconst10)*(((((sj5)*(x1626)))+(((cj5)*(x1623)))+(((IkReal(-1.00000000000000))*(x1621)*(x1624)))+(((sj8)*(x1625)))+(((IkReal(-1.00000000000000))*(sj5)*(x1622)))))), ((gconst10)*(((((sj5)*(x1623)))+(((IkReal(-1.00000000000000))*(cj5)*(x1626)))+(((cj5)*(x1622)))+(((sj8)*(x1621)))+(((x1624)*(x1625)))))));
7232 sj4array[0]=IKsin(j4array[0]);
7233 cj4array[0]=IKcos(j4array[0]);
7234 if( j4array[0] > IKPI )
7235 {
7236  j4array[0]-=IK2PI;
7237 }
7238 else if( j4array[0] < -IKPI )
7239 { j4array[0]+=IK2PI;
7240 }
7241 j4valid[0] = true;
7242 for(int ij4 = 0; ij4 < 1; ++ij4)
7243 {
7244 if( !j4valid[ij4] )
7245 {
7246  continue;
7247 }
7248 _ij4[0] = ij4; _ij4[1] = -1;
7249 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
7250 {
7251 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
7252 {
7253  j4valid[iij4]=false; _ij4[1] = iij4; break;
7254 }
7255 }
7256 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
7257 {
7258 IkReal evalcond[4];
7259 IkReal x1627=IKsin(j4);
7260 IkReal x1628=IKcos(j4);
7261 IkReal x1629=((IkReal(1.00000000000000))*(cj8));
7262 IkReal x1630=((cj3)*(r01));
7263 IkReal x1631=((cj3)*(r00));
7264 IkReal x1632=((cj7)*(cj8));
7265 IkReal x1633=((r11)*(sj3));
7266 IkReal x1634=((IkReal(1.00000000000000))*(sj8));
7267 IkReal x1635=((r10)*(sj3));
7268 IkReal x1636=((sj5)*(x1628));
7269 IkReal x1637=((cj5)*(x1627));
7270 IkReal x1638=((cj5)*(x1628));
7271 IkReal x1639=((sj5)*(x1627));
7272 IkReal x1640=((x1636)+(x1637));
7273 evalcond[0]=((x1640)+(((cj8)*(r21)))+(((r20)*(sj8))));
7274 evalcond[1]=((x1639)+(((IkReal(-1.00000000000000))*(x1638)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x1629)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
7275 evalcond[2]=((((IkReal(-1.00000000000000))*(x1634)*(x1635)))+(x1638)+(((IkReal(-1.00000000000000))*(x1639)))+(((IkReal(-1.00000000000000))*(x1629)*(x1633)))+(((IkReal(-1.00000000000000))*(x1629)*(x1630)))+(((IkReal(-1.00000000000000))*(x1631)*(x1634))));
7276 evalcond[3]=((((r12)*(sj3)*(sj7)))+(x1640)+(((IkReal(-1.00000000000000))*(cj7)*(x1633)*(x1634)))+(((cj3)*(r02)*(sj7)))+(((x1632)*(x1635)))+(((x1631)*(x1632)))+(((IkReal(-1.00000000000000))*(cj7)*(x1630)*(x1634))));
7277 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
7278 {
7279 continue;
7280 }
7281 }
7282 
7283 {
7284 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7285 vinfos[0].jointtype = 1;
7286 vinfos[0].foffset = j3;
7287 vinfos[0].indices[0] = _ij3[0];
7288 vinfos[0].indices[1] = _ij3[1];
7289 vinfos[0].maxsolutions = _nj3;
7290 vinfos[1].jointtype = 1;
7291 vinfos[1].foffset = j4;
7292 vinfos[1].indices[0] = _ij4[0];
7293 vinfos[1].indices[1] = _ij4[1];
7294 vinfos[1].maxsolutions = _nj4;
7295 vinfos[2].jointtype = 1;
7296 vinfos[2].foffset = j5;
7297 vinfos[2].indices[0] = _ij5[0];
7298 vinfos[2].indices[1] = _ij5[1];
7299 vinfos[2].maxsolutions = _nj5;
7300 vinfos[3].jointtype = 1;
7301 vinfos[3].foffset = j6;
7302 vinfos[3].indices[0] = _ij6[0];
7303 vinfos[3].indices[1] = _ij6[1];
7304 vinfos[3].maxsolutions = _nj6;
7305 vinfos[4].jointtype = 1;
7306 vinfos[4].foffset = j7;
7307 vinfos[4].indices[0] = _ij7[0];
7308 vinfos[4].indices[1] = _ij7[1];
7309 vinfos[4].maxsolutions = _nj7;
7310 vinfos[5].jointtype = 1;
7311 vinfos[5].foffset = j8;
7312 vinfos[5].indices[0] = _ij8[0];
7313 vinfos[5].indices[1] = _ij8[1];
7314 vinfos[5].maxsolutions = _nj8;
7315 std::vector<int> vfree(0);
7316 solutions.AddSolution(vinfos,vfree);
7317 }
7318 }
7319 }
7320 
7321 }
7322 
7323 }
7324 
7325 } else
7326 {
7327 IkReal x1641=((cj3)*(cj8));
7328 IkReal x1642=((IkReal(1.00000000000000))*(sj7));
7329 IkReal x1643=((cj8)*(npx));
7330 IkReal x1644=((cj8)*(sj3));
7331 IkReal x1645=((npy)*(sj8));
7332 IkReal x1646=((r02)*(sj3));
7333 IkReal x1647=((IkReal(1.00000000000000))*(r11));
7334 IkReal x1648=((cj3)*(r12));
7335 IkReal x1649=((IkReal(1.00000000000000))*(cj7));
7336 IkReal x1650=((sj3)*(sj8));
7337 IkReal x1651=((IkReal(1.00000000000000))*(cj3)*(sj8));
7338 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
7339 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
7340 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
7341 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x1642)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(x1643)*(x1649)))+(((cj7)*(x1645))));
7342 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1641)*(x1647)))+(((IkReal(-1.00000000000000))*(r10)*(x1651)))+(((r00)*(x1650)))+(((r01)*(x1644))));
7343 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x1642)*(x1643)))+(((cj7)*(npz)))+(((sj7)*(x1645)))+(((IkReal(-0.250000000000000))*(sj5))));
7344 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x1651)))+(((IkReal(-1.00000000000000))*(x1644)*(x1647)))+(((IkReal(-1.00000000000000))*(r01)*(x1641)))+(((IkReal(-1.00000000000000))*(r10)*(x1650))));
7345 evalcond[7]=((((cj7)*(r01)*(x1650)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x1647)))+(((cj7)*(r10)*(x1641)))+(((IkReal(-1.00000000000000))*(x1642)*(x1646)))+(((IkReal(-1.00000000000000))*(r00)*(x1644)*(x1649)))+(((sj7)*(x1648))));
7346 evalcond[8]=((((cj7)*(x1646)))+(((IkReal(-1.00000000000000))*(x1648)*(x1649)))+(((r10)*(sj7)*(x1641)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x1642)))+(((r01)*(sj7)*(x1650)))+(((IkReal(-1.00000000000000))*(r00)*(x1642)*(x1644))));
7347 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
7348 {
7349 {
7350 IkReal dummyeval[1];
7351 IkReal gconst12;
7352 gconst12=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
7353 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
7354 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
7355 {
7356 {
7357 IkReal dummyeval[1];
7358 IkReal gconst13;
7359 gconst13=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
7360 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
7361 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
7362 {
7363 continue;
7364 
7365 } else
7366 {
7367 {
7368 IkReal j4array[1], cj4array[1], sj4array[1];
7369 bool j4valid[1]={false};
7370 _nj4 = 1;
7371 IkReal x1652=((cj3)*(cj5));
7372 IkReal x1653=((r02)*(sj7));
7373 IkReal x1654=((cj5)*(sj7));
7374 IkReal x1655=((cj3)*(sj5));
7375 IkReal x1656=((IkReal(1.00000000000000))*(sj8));
7376 IkReal x1657=((cj8)*(r10));
7377 IkReal x1658=((cj7)*(cj8));
7378 IkReal x1659=((IkReal(1.00000000000000))*(sj5));
7379 IkReal x1660=((r12)*(sj3));
7380 IkReal x1661=((cj7)*(sj5));
7381 IkReal x1662=((cj5)*(cj7)*(sj3));
7382 IkReal x1663=((cj7)*(r01)*(x1656));
7383 if( IKabs(((gconst13)*(((((r21)*(sj8)*(x1661)))+(((r00)*(x1652)*(x1658)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1659)))+(((IkReal(-1.00000000000000))*(r11)*(x1656)*(x1662)))+(((x1654)*(x1660)))+(((IkReal(-1.00000000000000))*(x1652)*(x1663)))+(((x1657)*(x1662)))+(((IkReal(-1.00000000000000))*(r20)*(x1658)*(x1659)))+(((x1652)*(x1653))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst13)*(((((cj5)*(r20)*(x1658)))+(((r22)*(x1654)))+(((sj5)*(sj7)*(x1660)))+(((sj3)*(x1657)*(x1661)))+(((IkReal(-1.00000000000000))*(x1655)*(x1663)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(r21)*(x1656)))+(((r00)*(x1655)*(x1658)))+(((x1653)*(x1655)))+(((IkReal(-1.00000000000000))*(r11)*(sj3)*(x1656)*(x1661))))))) < IKFAST_ATAN2_MAGTHRESH )
7384  continue;
7385 j4array[0]=IKatan2(((gconst13)*(((((r21)*(sj8)*(x1661)))+(((r00)*(x1652)*(x1658)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1659)))+(((IkReal(-1.00000000000000))*(r11)*(x1656)*(x1662)))+(((x1654)*(x1660)))+(((IkReal(-1.00000000000000))*(x1652)*(x1663)))+(((x1657)*(x1662)))+(((IkReal(-1.00000000000000))*(r20)*(x1658)*(x1659)))+(((x1652)*(x1653)))))), ((gconst13)*(((((cj5)*(r20)*(x1658)))+(((r22)*(x1654)))+(((sj5)*(sj7)*(x1660)))+(((sj3)*(x1657)*(x1661)))+(((IkReal(-1.00000000000000))*(x1655)*(x1663)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(r21)*(x1656)))+(((r00)*(x1655)*(x1658)))+(((x1653)*(x1655)))+(((IkReal(-1.00000000000000))*(r11)*(sj3)*(x1656)*(x1661)))))));
7386 sj4array[0]=IKsin(j4array[0]);
7387 cj4array[0]=IKcos(j4array[0]);
7388 if( j4array[0] > IKPI )
7389 {
7390  j4array[0]-=IK2PI;
7391 }
7392 else if( j4array[0] < -IKPI )
7393 { j4array[0]+=IK2PI;
7394 }
7395 j4valid[0] = true;
7396 for(int ij4 = 0; ij4 < 1; ++ij4)
7397 {
7398 if( !j4valid[ij4] )
7399 {
7400  continue;
7401 }
7402 _ij4[0] = ij4; _ij4[1] = -1;
7403 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
7404 {
7405 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
7406 {
7407  j4valid[iij4]=false; _ij4[1] = iij4; break;
7408 }
7409 }
7410 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
7411 {
7412 IkReal evalcond[4];
7413 IkReal x1664=IKcos(j4);
7414 IkReal x1665=IKsin(j4);
7415 IkReal x1666=((IkReal(1.00000000000000))*(cj7));
7416 IkReal x1667=((cj8)*(r20));
7417 IkReal x1668=((cj3)*(r02));
7418 IkReal x1669=((IkReal(1.00000000000000))*(sj7));
7419 IkReal x1670=((sj3)*(sj7));
7420 IkReal x1671=((r21)*(sj8));
7421 IkReal x1672=((cj8)*(r10));
7422 IkReal x1673=((sj5)*(x1664));
7423 IkReal x1674=((cj5)*(x1665));
7424 IkReal x1675=((r11)*(sj3)*(sj8));
7425 IkReal x1676=((cj3)*(cj8)*(r00));
7426 IkReal x1677=((cj5)*(x1664));
7427 IkReal x1678=((cj3)*(r01)*(sj8));
7428 IkReal x1679=((sj5)*(x1665));
7429 IkReal x1680=((x1674)+(x1673));
7430 evalcond[0]=((x1679)+(((IkReal(-1.00000000000000))*(r22)*(x1669)))+(((IkReal(-1.00000000000000))*(x1677)))+(((cj7)*(x1671)))+(((IkReal(-1.00000000000000))*(x1666)*(x1667))));
7431 evalcond[1]=((x1680)+(((IkReal(-1.00000000000000))*(x1667)*(x1669)))+(((sj7)*(x1671)))+(((cj7)*(r22))));
7432 evalcond[2]=((x1680)+(((cj7)*(sj3)*(x1672)))+(((IkReal(-1.00000000000000))*(x1666)*(x1675)))+(((IkReal(-1.00000000000000))*(x1666)*(x1678)))+(((cj7)*(x1676)))+(((sj7)*(x1668)))+(((r12)*(x1670))));
7433 evalcond[3]=((x1677)+(((IkReal(-1.00000000000000))*(x1669)*(x1678)))+(((IkReal(-1.00000000000000))*(x1669)*(x1675)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1666)))+(((sj7)*(x1676)))+(((IkReal(-1.00000000000000))*(x1679)))+(((IkReal(-1.00000000000000))*(x1666)*(x1668)))+(((x1670)*(x1672))));
7434 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
7435 {
7436 continue;
7437 }
7438 }
7439 
7440 {
7441 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7442 vinfos[0].jointtype = 1;
7443 vinfos[0].foffset = j3;
7444 vinfos[0].indices[0] = _ij3[0];
7445 vinfos[0].indices[1] = _ij3[1];
7446 vinfos[0].maxsolutions = _nj3;
7447 vinfos[1].jointtype = 1;
7448 vinfos[1].foffset = j4;
7449 vinfos[1].indices[0] = _ij4[0];
7450 vinfos[1].indices[1] = _ij4[1];
7451 vinfos[1].maxsolutions = _nj4;
7452 vinfos[2].jointtype = 1;
7453 vinfos[2].foffset = j5;
7454 vinfos[2].indices[0] = _ij5[0];
7455 vinfos[2].indices[1] = _ij5[1];
7456 vinfos[2].maxsolutions = _nj5;
7457 vinfos[3].jointtype = 1;
7458 vinfos[3].foffset = j6;
7459 vinfos[3].indices[0] = _ij6[0];
7460 vinfos[3].indices[1] = _ij6[1];
7461 vinfos[3].maxsolutions = _nj6;
7462 vinfos[4].jointtype = 1;
7463 vinfos[4].foffset = j7;
7464 vinfos[4].indices[0] = _ij7[0];
7465 vinfos[4].indices[1] = _ij7[1];
7466 vinfos[4].maxsolutions = _nj7;
7467 vinfos[5].jointtype = 1;
7468 vinfos[5].foffset = j8;
7469 vinfos[5].indices[0] = _ij8[0];
7470 vinfos[5].indices[1] = _ij8[1];
7471 vinfos[5].maxsolutions = _nj8;
7472 std::vector<int> vfree(0);
7473 solutions.AddSolution(vinfos,vfree);
7474 }
7475 }
7476 }
7477 
7478 }
7479 
7480 }
7481 
7482 } else
7483 {
7484 {
7485 IkReal j4array[1], cj4array[1], sj4array[1];
7486 bool j4valid[1]={false};
7487 _nj4 = 1;
7488 IkReal x1681=((sj5)*(sj7));
7489 IkReal x1682=((r21)*(sj8));
7490 IkReal x1683=((cj5)*(sj7));
7491 IkReal x1684=((cj8)*(r20));
7492 IkReal x1685=((cj5)*(cj7));
7493 IkReal x1686=((cj7)*(sj5));
7494 if( IKabs(((gconst12)*(((((IkReal(-1.00000000000000))*(r22)*(x1681)))+(((r22)*(x1685)))+(((IkReal(-1.00000000000000))*(x1684)*(x1686)))+(((IkReal(-1.00000000000000))*(x1683)*(x1684)))+(((x1682)*(x1683)))+(((x1682)*(x1686))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((x1681)*(x1682)))+(((r22)*(x1683)))+(((r22)*(x1686)))+(((IkReal(-1.00000000000000))*(x1681)*(x1684)))+(((x1684)*(x1685)))+(((IkReal(-1.00000000000000))*(x1682)*(x1685))))))) < IKFAST_ATAN2_MAGTHRESH )
7495  continue;
7496 j4array[0]=IKatan2(((gconst12)*(((((IkReal(-1.00000000000000))*(r22)*(x1681)))+(((r22)*(x1685)))+(((IkReal(-1.00000000000000))*(x1684)*(x1686)))+(((IkReal(-1.00000000000000))*(x1683)*(x1684)))+(((x1682)*(x1683)))+(((x1682)*(x1686)))))), ((gconst12)*(((((x1681)*(x1682)))+(((r22)*(x1683)))+(((r22)*(x1686)))+(((IkReal(-1.00000000000000))*(x1681)*(x1684)))+(((x1684)*(x1685)))+(((IkReal(-1.00000000000000))*(x1682)*(x1685)))))));
7497 sj4array[0]=IKsin(j4array[0]);
7498 cj4array[0]=IKcos(j4array[0]);
7499 if( j4array[0] > IKPI )
7500 {
7501  j4array[0]-=IK2PI;
7502 }
7503 else if( j4array[0] < -IKPI )
7504 { j4array[0]+=IK2PI;
7505 }
7506 j4valid[0] = true;
7507 for(int ij4 = 0; ij4 < 1; ++ij4)
7508 {
7509 if( !j4valid[ij4] )
7510 {
7511  continue;
7512 }
7513 _ij4[0] = ij4; _ij4[1] = -1;
7514 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
7515 {
7516 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
7517 {
7518  j4valid[iij4]=false; _ij4[1] = iij4; break;
7519 }
7520 }
7521 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
7522 {
7523 IkReal evalcond[4];
7524 IkReal x1687=IKcos(j4);
7525 IkReal x1688=IKsin(j4);
7526 IkReal x1689=((IkReal(1.00000000000000))*(cj7));
7527 IkReal x1690=((cj8)*(r20));
7528 IkReal x1691=((cj3)*(r02));
7529 IkReal x1692=((IkReal(1.00000000000000))*(sj7));
7530 IkReal x1693=((sj3)*(sj7));
7531 IkReal x1694=((r21)*(sj8));
7532 IkReal x1695=((cj8)*(r10));
7533 IkReal x1696=((sj5)*(x1687));
7534 IkReal x1697=((cj5)*(x1688));
7535 IkReal x1698=((r11)*(sj3)*(sj8));
7536 IkReal x1699=((cj3)*(cj8)*(r00));
7537 IkReal x1700=((cj5)*(x1687));
7538 IkReal x1701=((cj3)*(r01)*(sj8));
7539 IkReal x1702=((sj5)*(x1688));
7540 IkReal x1703=((x1696)+(x1697));
7541 evalcond[0]=((x1702)+(((IkReal(-1.00000000000000))*(x1700)))+(((IkReal(-1.00000000000000))*(r22)*(x1692)))+(((cj7)*(x1694)))+(((IkReal(-1.00000000000000))*(x1689)*(x1690))));
7542 evalcond[1]=((x1703)+(((IkReal(-1.00000000000000))*(x1690)*(x1692)))+(((sj7)*(x1694)))+(((cj7)*(r22))));
7543 evalcond[2]=((((r12)*(x1693)))+(x1703)+(((sj7)*(x1691)))+(((IkReal(-1.00000000000000))*(x1689)*(x1701)))+(((cj7)*(sj3)*(x1695)))+(((cj7)*(x1699)))+(((IkReal(-1.00000000000000))*(x1689)*(x1698))));
7544 evalcond[3]=((((IkReal(-1.00000000000000))*(x1692)*(x1698)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1689)))+(x1700)+(((IkReal(-1.00000000000000))*(x1702)))+(((sj7)*(x1699)))+(((x1693)*(x1695)))+(((IkReal(-1.00000000000000))*(x1692)*(x1701)))+(((IkReal(-1.00000000000000))*(x1689)*(x1691))));
7545 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
7546 {
7547 continue;
7548 }
7549 }
7550 
7551 {
7552 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7553 vinfos[0].jointtype = 1;
7554 vinfos[0].foffset = j3;
7555 vinfos[0].indices[0] = _ij3[0];
7556 vinfos[0].indices[1] = _ij3[1];
7557 vinfos[0].maxsolutions = _nj3;
7558 vinfos[1].jointtype = 1;
7559 vinfos[1].foffset = j4;
7560 vinfos[1].indices[0] = _ij4[0];
7561 vinfos[1].indices[1] = _ij4[1];
7562 vinfos[1].maxsolutions = _nj4;
7563 vinfos[2].jointtype = 1;
7564 vinfos[2].foffset = j5;
7565 vinfos[2].indices[0] = _ij5[0];
7566 vinfos[2].indices[1] = _ij5[1];
7567 vinfos[2].maxsolutions = _nj5;
7568 vinfos[3].jointtype = 1;
7569 vinfos[3].foffset = j6;
7570 vinfos[3].indices[0] = _ij6[0];
7571 vinfos[3].indices[1] = _ij6[1];
7572 vinfos[3].maxsolutions = _nj6;
7573 vinfos[4].jointtype = 1;
7574 vinfos[4].foffset = j7;
7575 vinfos[4].indices[0] = _ij7[0];
7576 vinfos[4].indices[1] = _ij7[1];
7577 vinfos[4].maxsolutions = _nj7;
7578 vinfos[5].jointtype = 1;
7579 vinfos[5].foffset = j8;
7580 vinfos[5].indices[0] = _ij8[0];
7581 vinfos[5].indices[1] = _ij8[1];
7582 vinfos[5].maxsolutions = _nj8;
7583 std::vector<int> vfree(0);
7584 solutions.AddSolution(vinfos,vfree);
7585 }
7586 }
7587 }
7588 
7589 }
7590 
7591 }
7592 
7593 } else
7594 {
7595 IkReal x1704=((cj3)*(cj8));
7596 IkReal x1705=((IkReal(1.00000000000000))*(sj7));
7597 IkReal x1706=((cj8)*(npx));
7598 IkReal x1707=((cj8)*(sj3));
7599 IkReal x1708=((npy)*(sj8));
7600 IkReal x1709=((r02)*(sj3));
7601 IkReal x1710=((IkReal(1.00000000000000))*(r11));
7602 IkReal x1711=((cj3)*(r12));
7603 IkReal x1712=((IkReal(1.00000000000000))*(cj7));
7604 IkReal x1713=((sj3)*(sj8));
7605 IkReal x1714=((IkReal(1.00000000000000))*(cj3)*(sj8));
7606 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
7607 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
7608 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
7609 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((cj7)*(x1708)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(x1706)*(x1712)))+(((IkReal(-1.00000000000000))*(npz)*(x1705))));
7610 evalcond[4]=((IkReal(-1.00000000000000))+(((r01)*(x1707)))+(((r00)*(x1713)))+(((IkReal(-1.00000000000000))*(r10)*(x1714)))+(((IkReal(-1.00000000000000))*(x1704)*(x1710))));
7611 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(0.250000000000000))*(sj5)))+(((IkReal(-1.00000000000000))*(x1705)*(x1706)))+(((cj7)*(npz)))+(((sj7)*(x1708))));
7612 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x1714)))+(((IkReal(-1.00000000000000))*(r01)*(x1704)))+(((IkReal(-1.00000000000000))*(x1707)*(x1710)))+(((IkReal(-1.00000000000000))*(r10)*(x1713))));
7613 evalcond[7]=((((cj7)*(r10)*(x1704)))+(((IkReal(-1.00000000000000))*(r00)*(x1707)*(x1712)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x1710)))+(((IkReal(-1.00000000000000))*(x1705)*(x1709)))+(((sj7)*(x1711)))+(((cj7)*(r01)*(x1713))));
7614 evalcond[8]=((((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x1705)))+(((r01)*(sj7)*(x1713)))+(((cj7)*(x1709)))+(((IkReal(-1.00000000000000))*(x1711)*(x1712)))+(((IkReal(-1.00000000000000))*(r00)*(x1705)*(x1707)))+(((r10)*(sj7)*(x1704))));
7615 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
7616 {
7617 {
7618 IkReal dummyeval[1];
7619 IkReal gconst14;
7620 gconst14=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
7621 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
7622 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
7623 {
7624 {
7625 IkReal dummyeval[1];
7626 IkReal gconst15;
7627 gconst15=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
7628 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
7629 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
7630 {
7631 continue;
7632 
7633 } else
7634 {
7635 {
7636 IkReal j4array[1], cj4array[1], sj4array[1];
7637 bool j4valid[1]={false};
7638 _nj4 = 1;
7639 IkReal x1715=((cj3)*(cj5));
7640 IkReal x1716=((r02)*(sj7));
7641 IkReal x1717=((cj8)*(r00));
7642 IkReal x1718=((cj5)*(sj7));
7643 IkReal x1719=((cj5)*(sj3));
7644 IkReal x1720=((sj3)*(sj5));
7645 IkReal x1721=((IkReal(1.00000000000000))*(sj5));
7646 IkReal x1722=((cj3)*(cj7)*(sj5));
7647 IkReal x1723=((IkReal(1.00000000000000))*(cj7)*(sj8));
7648 IkReal x1724=((cj7)*(cj8)*(r10));
7649 IkReal x1725=((cj7)*(cj8)*(r20));
7650 if( IKabs(((gconst15)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r01)*(x1715)*(x1723)))+(((r12)*(sj3)*(x1718)))+(((IkReal(-1.00000000000000))*(r11)*(x1719)*(x1723)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1721)))+(((x1715)*(x1716)))+(((x1719)*(x1724)))+(((cj7)*(x1715)*(x1717)))+(((IkReal(-1.00000000000000))*(x1721)*(x1725))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst15)*(((((r22)*(x1718)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x1721)))+(((IkReal(-1.00000000000000))*(r11)*(x1720)*(x1723)))+(((cj3)*(sj5)*(x1716)))+(((x1717)*(x1722)))+(((x1720)*(x1724)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x1723)))+(((cj5)*(x1725)))+(((r12)*(sj7)*(x1720))))))) < IKFAST_ATAN2_MAGTHRESH )
7651  continue;
7652 j4array[0]=IKatan2(((gconst15)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r01)*(x1715)*(x1723)))+(((r12)*(sj3)*(x1718)))+(((IkReal(-1.00000000000000))*(r11)*(x1719)*(x1723)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x1721)))+(((x1715)*(x1716)))+(((x1719)*(x1724)))+(((cj7)*(x1715)*(x1717)))+(((IkReal(-1.00000000000000))*(x1721)*(x1725)))))), ((gconst15)*(((((r22)*(x1718)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x1721)))+(((IkReal(-1.00000000000000))*(r11)*(x1720)*(x1723)))+(((cj3)*(sj5)*(x1716)))+(((x1717)*(x1722)))+(((x1720)*(x1724)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x1723)))+(((cj5)*(x1725)))+(((r12)*(sj7)*(x1720)))))));
7653 sj4array[0]=IKsin(j4array[0]);
7654 cj4array[0]=IKcos(j4array[0]);
7655 if( j4array[0] > IKPI )
7656 {
7657  j4array[0]-=IK2PI;
7658 }
7659 else if( j4array[0] < -IKPI )
7660 { j4array[0]+=IK2PI;
7661 }
7662 j4valid[0] = true;
7663 for(int ij4 = 0; ij4 < 1; ++ij4)
7664 {
7665 if( !j4valid[ij4] )
7666 {
7667  continue;
7668 }
7669 _ij4[0] = ij4; _ij4[1] = -1;
7670 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
7671 {
7672 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
7673 {
7674  j4valid[iij4]=false; _ij4[1] = iij4; break;
7675 }
7676 }
7677 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
7678 {
7679 IkReal evalcond[4];
7680 IkReal x1726=IKcos(j4);
7681 IkReal x1727=IKsin(j4);
7682 IkReal x1728=((IkReal(1.00000000000000))*(cj7));
7683 IkReal x1729=((cj8)*(r20));
7684 IkReal x1730=((cj3)*(r02));
7685 IkReal x1731=((IkReal(1.00000000000000))*(sj7));
7686 IkReal x1732=((sj3)*(sj7));
7687 IkReal x1733=((r21)*(sj8));
7688 IkReal x1734=((IkReal(1.00000000000000))*(cj5));
7689 IkReal x1735=((cj8)*(r10));
7690 IkReal x1736=((sj5)*(x1727));
7691 IkReal x1737=((sj5)*(x1726));
7692 IkReal x1738=((r11)*(sj3)*(sj8));
7693 IkReal x1739=((cj3)*(cj8)*(r00));
7694 IkReal x1740=((cj3)*(r01)*(sj8));
7695 IkReal x1741=((x1726)*(x1734));
7696 evalcond[0]=((x1736)+(((IkReal(-1.00000000000000))*(x1728)*(x1729)))+(((IkReal(-1.00000000000000))*(x1741)))+(((cj7)*(x1733)))+(((IkReal(-1.00000000000000))*(r22)*(x1731))));
7697 evalcond[1]=((((sj7)*(x1733)))+(((IkReal(-1.00000000000000))*(x1729)*(x1731)))+(((IkReal(-1.00000000000000))*(x1737)))+(((IkReal(-1.00000000000000))*(x1727)*(x1734)))+(((cj7)*(r22))));
7698 evalcond[2]=((((IkReal(-1.00000000000000))*(x1728)*(x1738)))+(x1737)+(((sj7)*(x1730)))+(((IkReal(-1.00000000000000))*(x1728)*(x1740)))+(((cj7)*(sj3)*(x1735)))+(((r12)*(x1732)))+(((cj5)*(x1727)))+(((cj7)*(x1739))));
7699 evalcond[3]=((((IkReal(-1.00000000000000))*(x1731)*(x1738)))+(((IkReal(-1.00000000000000))*(x1728)*(x1730)))+(x1736)+(((sj7)*(x1739)))+(((IkReal(-1.00000000000000))*(x1741)))+(((x1732)*(x1735)))+(((IkReal(-1.00000000000000))*(x1731)*(x1740)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1728))));
7700 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
7701 {
7702 continue;
7703 }
7704 }
7705 
7706 {
7707 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7708 vinfos[0].jointtype = 1;
7709 vinfos[0].foffset = j3;
7710 vinfos[0].indices[0] = _ij3[0];
7711 vinfos[0].indices[1] = _ij3[1];
7712 vinfos[0].maxsolutions = _nj3;
7713 vinfos[1].jointtype = 1;
7714 vinfos[1].foffset = j4;
7715 vinfos[1].indices[0] = _ij4[0];
7716 vinfos[1].indices[1] = _ij4[1];
7717 vinfos[1].maxsolutions = _nj4;
7718 vinfos[2].jointtype = 1;
7719 vinfos[2].foffset = j5;
7720 vinfos[2].indices[0] = _ij5[0];
7721 vinfos[2].indices[1] = _ij5[1];
7722 vinfos[2].maxsolutions = _nj5;
7723 vinfos[3].jointtype = 1;
7724 vinfos[3].foffset = j6;
7725 vinfos[3].indices[0] = _ij6[0];
7726 vinfos[3].indices[1] = _ij6[1];
7727 vinfos[3].maxsolutions = _nj6;
7728 vinfos[4].jointtype = 1;
7729 vinfos[4].foffset = j7;
7730 vinfos[4].indices[0] = _ij7[0];
7731 vinfos[4].indices[1] = _ij7[1];
7732 vinfos[4].maxsolutions = _nj7;
7733 vinfos[5].jointtype = 1;
7734 vinfos[5].foffset = j8;
7735 vinfos[5].indices[0] = _ij8[0];
7736 vinfos[5].indices[1] = _ij8[1];
7737 vinfos[5].maxsolutions = _nj8;
7738 std::vector<int> vfree(0);
7739 solutions.AddSolution(vinfos,vfree);
7740 }
7741 }
7742 }
7743 
7744 }
7745 
7746 }
7747 
7748 } else
7749 {
7750 {
7751 IkReal j4array[1], cj4array[1], sj4array[1];
7752 bool j4valid[1]={false};
7753 _nj4 = 1;
7754 IkReal x1742=((IkReal(1.00000000000000))*(sj5));
7755 IkReal x1743=((cj7)*(sj5));
7756 IkReal x1744=((cj8)*(r20));
7757 IkReal x1745=((cj5)*(cj7));
7758 IkReal x1746=((sj5)*(sj7));
7759 IkReal x1747=((r21)*(sj8));
7760 IkReal x1748=((cj7)*(x1747));
7761 IkReal x1749=((IkReal(1.00000000000000))*(cj5)*(sj7));
7762 if( IKabs(((gconst14)*(((((r22)*(x1745)))+(((r22)*(x1746)))+(((cj5)*(sj7)*(x1747)))+(((IkReal(-1.00000000000000))*(x1744)*(x1749)))+(((x1743)*(x1744)))+(((IkReal(-1.00000000000000))*(x1742)*(x1748))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst14)*(((((r22)*(x1743)))+(((x1745)*(x1747)))+(((x1746)*(x1747)))+(((IkReal(-1.00000000000000))*(r22)*(x1749)))+(((IkReal(-1.00000000000000))*(sj7)*(x1742)*(x1744)))+(((IkReal(-1.00000000000000))*(x1744)*(x1745))))))) < IKFAST_ATAN2_MAGTHRESH )
7763  continue;
7764 j4array[0]=IKatan2(((gconst14)*(((((r22)*(x1745)))+(((r22)*(x1746)))+(((cj5)*(sj7)*(x1747)))+(((IkReal(-1.00000000000000))*(x1744)*(x1749)))+(((x1743)*(x1744)))+(((IkReal(-1.00000000000000))*(x1742)*(x1748)))))), ((gconst14)*(((((r22)*(x1743)))+(((x1745)*(x1747)))+(((x1746)*(x1747)))+(((IkReal(-1.00000000000000))*(r22)*(x1749)))+(((IkReal(-1.00000000000000))*(sj7)*(x1742)*(x1744)))+(((IkReal(-1.00000000000000))*(x1744)*(x1745)))))));
7765 sj4array[0]=IKsin(j4array[0]);
7766 cj4array[0]=IKcos(j4array[0]);
7767 if( j4array[0] > IKPI )
7768 {
7769  j4array[0]-=IK2PI;
7770 }
7771 else if( j4array[0] < -IKPI )
7772 { j4array[0]+=IK2PI;
7773 }
7774 j4valid[0] = true;
7775 for(int ij4 = 0; ij4 < 1; ++ij4)
7776 {
7777 if( !j4valid[ij4] )
7778 {
7779  continue;
7780 }
7781 _ij4[0] = ij4; _ij4[1] = -1;
7782 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
7783 {
7784 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
7785 {
7786  j4valid[iij4]=false; _ij4[1] = iij4; break;
7787 }
7788 }
7789 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
7790 {
7791 IkReal evalcond[4];
7792 IkReal x1750=IKcos(j4);
7793 IkReal x1751=IKsin(j4);
7794 IkReal x1752=((IkReal(1.00000000000000))*(cj7));
7795 IkReal x1753=((cj8)*(r20));
7796 IkReal x1754=((cj3)*(r02));
7797 IkReal x1755=((IkReal(1.00000000000000))*(sj7));
7798 IkReal x1756=((sj3)*(sj7));
7799 IkReal x1757=((r21)*(sj8));
7800 IkReal x1758=((IkReal(1.00000000000000))*(cj5));
7801 IkReal x1759=((cj8)*(r10));
7802 IkReal x1760=((sj5)*(x1751));
7803 IkReal x1761=((sj5)*(x1750));
7804 IkReal x1762=((r11)*(sj3)*(sj8));
7805 IkReal x1763=((cj3)*(cj8)*(r00));
7806 IkReal x1764=((cj3)*(r01)*(sj8));
7807 IkReal x1765=((x1750)*(x1758));
7808 evalcond[0]=((((IkReal(-1.00000000000000))*(x1765)))+(x1760)+(((IkReal(-1.00000000000000))*(r22)*(x1755)))+(((cj7)*(x1757)))+(((IkReal(-1.00000000000000))*(x1752)*(x1753))));
7809 evalcond[1]=((((IkReal(-1.00000000000000))*(x1761)))+(((sj7)*(x1757)))+(((IkReal(-1.00000000000000))*(x1751)*(x1758)))+(((IkReal(-1.00000000000000))*(x1753)*(x1755)))+(((cj7)*(r22))));
7810 evalcond[2]=((((IkReal(-1.00000000000000))*(x1752)*(x1764)))+(((IkReal(-1.00000000000000))*(x1752)*(x1762)))+(((cj5)*(x1751)))+(((cj7)*(x1763)))+(x1761)+(((cj7)*(sj3)*(x1759)))+(((sj7)*(x1754)))+(((r12)*(x1756))));
7811 evalcond[3]=((((sj7)*(x1763)))+(((IkReal(-1.00000000000000))*(x1765)))+(x1760)+(((IkReal(-1.00000000000000))*(x1755)*(x1762)))+(((IkReal(-1.00000000000000))*(x1755)*(x1764)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1752)))+(((IkReal(-1.00000000000000))*(x1752)*(x1754)))+(((x1756)*(x1759))));
7812 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
7813 {
7814 continue;
7815 }
7816 }
7817 
7818 {
7819 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7820 vinfos[0].jointtype = 1;
7821 vinfos[0].foffset = j3;
7822 vinfos[0].indices[0] = _ij3[0];
7823 vinfos[0].indices[1] = _ij3[1];
7824 vinfos[0].maxsolutions = _nj3;
7825 vinfos[1].jointtype = 1;
7826 vinfos[1].foffset = j4;
7827 vinfos[1].indices[0] = _ij4[0];
7828 vinfos[1].indices[1] = _ij4[1];
7829 vinfos[1].maxsolutions = _nj4;
7830 vinfos[2].jointtype = 1;
7831 vinfos[2].foffset = j5;
7832 vinfos[2].indices[0] = _ij5[0];
7833 vinfos[2].indices[1] = _ij5[1];
7834 vinfos[2].maxsolutions = _nj5;
7835 vinfos[3].jointtype = 1;
7836 vinfos[3].foffset = j6;
7837 vinfos[3].indices[0] = _ij6[0];
7838 vinfos[3].indices[1] = _ij6[1];
7839 vinfos[3].maxsolutions = _nj6;
7840 vinfos[4].jointtype = 1;
7841 vinfos[4].foffset = j7;
7842 vinfos[4].indices[0] = _ij7[0];
7843 vinfos[4].indices[1] = _ij7[1];
7844 vinfos[4].maxsolutions = _nj7;
7845 vinfos[5].jointtype = 1;
7846 vinfos[5].foffset = j8;
7847 vinfos[5].indices[0] = _ij8[0];
7848 vinfos[5].indices[1] = _ij8[1];
7849 vinfos[5].maxsolutions = _nj8;
7850 std::vector<int> vfree(0);
7851 solutions.AddSolution(vinfos,vfree);
7852 }
7853 }
7854 }
7855 
7856 }
7857 
7858 }
7859 
7860 } else
7861 {
7862 if( 1 )
7863 {
7864 continue;
7865 
7866 } else
7867 {
7868 }
7869 }
7870 }
7871 }
7872 }
7873 }
7874 
7875 } else
7876 {
7877 {
7878 IkReal j4array[1], cj4array[1], sj4array[1];
7879 bool j4valid[1]={false};
7880 _nj4 = 1;
7881 IkReal x1766=((r21)*(sj8));
7882 IkReal x1767=((IkReal(1.00000000000000))*(r22));
7883 IkReal x1768=((cj5)*(sj7));
7884 IkReal x1769=((cj6)*(cj7));
7885 IkReal x1770=((sj5)*(sj7));
7886 IkReal x1771=((cj5)*(cj8)*(r20));
7887 IkReal x1772=((IkReal(1.00000000000000))*(x1769));
7888 IkReal x1773=((cj8)*(r20)*(sj5));
7889 if( IKabs(((gconst7)*(((((cj6)*(r22)*(x1770)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x1767)))+(((cj8)*(r20)*(x1768)))+(((IkReal(-1.00000000000000))*(sj5)*(x1766)*(x1772)))+(((x1769)*(x1773)))+(((IkReal(-1.00000000000000))*(x1766)*(x1768))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((((IkReal(-1.00000000000000))*(x1766)*(x1770)))+(((cj8)*(r20)*(x1770)))+(((IkReal(-1.00000000000000))*(x1771)*(x1772)))+(((IkReal(-1.00000000000000))*(cj6)*(x1767)*(x1768)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x1767)))+(((cj5)*(x1766)*(x1769))))))) < IKFAST_ATAN2_MAGTHRESH )
7890  continue;
7891 j4array[0]=IKatan2(((gconst7)*(((((cj6)*(r22)*(x1770)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x1767)))+(((cj8)*(r20)*(x1768)))+(((IkReal(-1.00000000000000))*(sj5)*(x1766)*(x1772)))+(((x1769)*(x1773)))+(((IkReal(-1.00000000000000))*(x1766)*(x1768)))))), ((gconst7)*(((((IkReal(-1.00000000000000))*(x1766)*(x1770)))+(((cj8)*(r20)*(x1770)))+(((IkReal(-1.00000000000000))*(x1771)*(x1772)))+(((IkReal(-1.00000000000000))*(cj6)*(x1767)*(x1768)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x1767)))+(((cj5)*(x1766)*(x1769)))))));
7892 sj4array[0]=IKsin(j4array[0]);
7893 cj4array[0]=IKcos(j4array[0]);
7894 if( j4array[0] > IKPI )
7895 {
7896  j4array[0]-=IK2PI;
7897 }
7898 else if( j4array[0] < -IKPI )
7899 { j4array[0]+=IK2PI;
7900 }
7901 j4valid[0] = true;
7902 for(int ij4 = 0; ij4 < 1; ++ij4)
7903 {
7904 if( !j4valid[ij4] )
7905 {
7906  continue;
7907 }
7908 _ij4[0] = ij4; _ij4[1] = -1;
7909 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
7910 {
7911 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
7912 {
7913  j4valid[iij4]=false; _ij4[1] = iij4; break;
7914 }
7915 }
7916 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
7917 {
7918 IkReal evalcond[6];
7919 IkReal x1774=IKsin(j4);
7920 IkReal x1775=IKcos(j4);
7921 IkReal x1776=((IkReal(1.00000000000000))*(cj8));
7922 IkReal x1777=((cj3)*(r01));
7923 IkReal x1778=((IkReal(1.00000000000000))*(sj8));
7924 IkReal x1779=((r11)*(sj3));
7925 IkReal x1780=((cj3)*(r00));
7926 IkReal x1781=((IkReal(1.00000000000000))*(sj6));
7927 IkReal x1782=((IkReal(1.00000000000000))*(cj7));
7928 IkReal x1783=((cj3)*(r02));
7929 IkReal x1784=((sj3)*(sj7));
7930 IkReal x1785=((cj7)*(cj8));
7931 IkReal x1786=((r21)*(sj8));
7932 IkReal x1787=((r10)*(sj3));
7933 IkReal x1788=((sj5)*(x1775));
7934 IkReal x1789=((cj5)*(x1775));
7935 IkReal x1790=((cj6)*(x1774));
7936 IkReal x1791=((cj5)*(x1774));
7937 IkReal x1792=((sj5)*(x1774));
7938 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x1781)*(x1788)))+(((IkReal(-1.00000000000000))*(x1781)*(x1791)))+(((r20)*(sj8))));
7939 evalcond[1]=((((cj7)*(x1786)))+(x1792)+(((IkReal(-1.00000000000000))*(x1789)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x1776))));
7940 evalcond[2]=((((cj6)*(x1788)))+(((sj7)*(x1786)))+(((IkReal(-1.00000000000000))*(r20)*(sj7)*(x1776)))+(((cj7)*(r22)))+(((cj5)*(x1790))));
7941 evalcond[3]=((((sj6)*(x1792)))+(((IkReal(-1.00000000000000))*(x1776)*(x1779)))+(((IkReal(-1.00000000000000))*(x1776)*(x1777)))+(((IkReal(-1.00000000000000))*(x1778)*(x1780)))+(((IkReal(-1.00000000000000))*(x1778)*(x1787)))+(((IkReal(-1.00000000000000))*(x1781)*(x1789))));
7942 evalcond[4]=((x1788)+(x1791)+(((IkReal(-1.00000000000000))*(cj7)*(x1777)*(x1778)))+(((IkReal(-1.00000000000000))*(cj7)*(x1778)*(x1779)))+(((sj7)*(x1783)))+(((r12)*(x1784)))+(((x1785)*(x1787)))+(((x1780)*(x1785))));
7943 evalcond[5]=((((cj6)*(x1789)))+(((IkReal(-1.00000000000000))*(sj5)*(x1790)))+(((cj8)*(r10)*(x1784)))+(((cj8)*(sj7)*(x1780)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1782)))+(((IkReal(-1.00000000000000))*(sj7)*(x1777)*(x1778)))+(((IkReal(-1.00000000000000))*(x1782)*(x1783)))+(((IkReal(-1.00000000000000))*(sj7)*(x1778)*(x1779))));
7944 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
7945 {
7946 continue;
7947 }
7948 }
7949 
7950 {
7951 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7952 vinfos[0].jointtype = 1;
7953 vinfos[0].foffset = j3;
7954 vinfos[0].indices[0] = _ij3[0];
7955 vinfos[0].indices[1] = _ij3[1];
7956 vinfos[0].maxsolutions = _nj3;
7957 vinfos[1].jointtype = 1;
7958 vinfos[1].foffset = j4;
7959 vinfos[1].indices[0] = _ij4[0];
7960 vinfos[1].indices[1] = _ij4[1];
7961 vinfos[1].maxsolutions = _nj4;
7962 vinfos[2].jointtype = 1;
7963 vinfos[2].foffset = j5;
7964 vinfos[2].indices[0] = _ij5[0];
7965 vinfos[2].indices[1] = _ij5[1];
7966 vinfos[2].maxsolutions = _nj5;
7967 vinfos[3].jointtype = 1;
7968 vinfos[3].foffset = j6;
7969 vinfos[3].indices[0] = _ij6[0];
7970 vinfos[3].indices[1] = _ij6[1];
7971 vinfos[3].maxsolutions = _nj6;
7972 vinfos[4].jointtype = 1;
7973 vinfos[4].foffset = j7;
7974 vinfos[4].indices[0] = _ij7[0];
7975 vinfos[4].indices[1] = _ij7[1];
7976 vinfos[4].maxsolutions = _nj7;
7977 vinfos[5].jointtype = 1;
7978 vinfos[5].foffset = j8;
7979 vinfos[5].indices[0] = _ij8[0];
7980 vinfos[5].indices[1] = _ij8[1];
7981 vinfos[5].maxsolutions = _nj8;
7982 std::vector<int> vfree(0);
7983 solutions.AddSolution(vinfos,vfree);
7984 }
7985 }
7986 }
7987 
7988 }
7989 
7990 }
7991 
7992 } else
7993 {
7994 {
7995 IkReal j4array[1], cj4array[1], sj4array[1];
7996 bool j4valid[1]={false};
7997 _nj4 = 1;
7998 IkReal x1793=((sj5)*(sj6));
7999 IkReal x1794=((r22)*(sj7));
8000 IkReal x1795=((r20)*(sj8));
8001 IkReal x1796=((cj8)*(r21));
8002 IkReal x1797=((cj5)*(sj6));
8003 IkReal x1798=((cj7)*(cj8)*(r20));
8004 IkReal x1799=((cj7)*(r21)*(sj8));
8005 if( IKabs(((gconst6)*(((((x1793)*(x1798)))+(((x1793)*(x1794)))+(((IkReal(-1.00000000000000))*(x1793)*(x1799)))+(((cj5)*(x1796)))+(((cj5)*(x1795))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((((x1797)*(x1799)))+(((IkReal(-1.00000000000000))*(x1797)*(x1798)))+(((IkReal(-1.00000000000000))*(x1794)*(x1797)))+(((sj5)*(x1796)))+(((sj5)*(x1795))))))) < IKFAST_ATAN2_MAGTHRESH )
8006  continue;
8007 j4array[0]=IKatan2(((gconst6)*(((((x1793)*(x1798)))+(((x1793)*(x1794)))+(((IkReal(-1.00000000000000))*(x1793)*(x1799)))+(((cj5)*(x1796)))+(((cj5)*(x1795)))))), ((gconst6)*(((((x1797)*(x1799)))+(((IkReal(-1.00000000000000))*(x1797)*(x1798)))+(((IkReal(-1.00000000000000))*(x1794)*(x1797)))+(((sj5)*(x1796)))+(((sj5)*(x1795)))))));
8008 sj4array[0]=IKsin(j4array[0]);
8009 cj4array[0]=IKcos(j4array[0]);
8010 if( j4array[0] > IKPI )
8011 {
8012  j4array[0]-=IK2PI;
8013 }
8014 else if( j4array[0] < -IKPI )
8015 { j4array[0]+=IK2PI;
8016 }
8017 j4valid[0] = true;
8018 for(int ij4 = 0; ij4 < 1; ++ij4)
8019 {
8020 if( !j4valid[ij4] )
8021 {
8022  continue;
8023 }
8024 _ij4[0] = ij4; _ij4[1] = -1;
8025 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
8026 {
8027 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
8028 {
8029  j4valid[iij4]=false; _ij4[1] = iij4; break;
8030 }
8031 }
8032 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
8033 {
8034 IkReal evalcond[6];
8035 IkReal x1800=IKsin(j4);
8036 IkReal x1801=IKcos(j4);
8037 IkReal x1802=((IkReal(1.00000000000000))*(cj8));
8038 IkReal x1803=((cj3)*(r01));
8039 IkReal x1804=((IkReal(1.00000000000000))*(sj8));
8040 IkReal x1805=((r11)*(sj3));
8041 IkReal x1806=((cj3)*(r00));
8042 IkReal x1807=((IkReal(1.00000000000000))*(sj6));
8043 IkReal x1808=((IkReal(1.00000000000000))*(cj7));
8044 IkReal x1809=((cj3)*(r02));
8045 IkReal x1810=((sj3)*(sj7));
8046 IkReal x1811=((cj7)*(cj8));
8047 IkReal x1812=((r21)*(sj8));
8048 IkReal x1813=((r10)*(sj3));
8049 IkReal x1814=((sj5)*(x1801));
8050 IkReal x1815=((cj5)*(x1801));
8051 IkReal x1816=((cj6)*(x1800));
8052 IkReal x1817=((cj5)*(x1800));
8053 IkReal x1818=((sj5)*(x1800));
8054 evalcond[0]=((((IkReal(-1.00000000000000))*(x1807)*(x1817)))+(((IkReal(-1.00000000000000))*(x1807)*(x1814)))+(((cj8)*(r21)))+(((r20)*(sj8))));
8055 evalcond[1]=((x1818)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x1802)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x1815)))+(((cj7)*(x1812))));
8056 evalcond[2]=((((IkReal(-1.00000000000000))*(r20)*(sj7)*(x1802)))+(((cj6)*(x1814)))+(((cj7)*(r22)))+(((cj5)*(x1816)))+(((sj7)*(x1812))));
8057 evalcond[3]=((((IkReal(-1.00000000000000))*(x1804)*(x1813)))+(((IkReal(-1.00000000000000))*(x1807)*(x1815)))+(((IkReal(-1.00000000000000))*(x1804)*(x1806)))+(((IkReal(-1.00000000000000))*(x1802)*(x1803)))+(((IkReal(-1.00000000000000))*(x1802)*(x1805)))+(((sj6)*(x1818))));
8058 evalcond[4]=((x1814)+(x1817)+(((IkReal(-1.00000000000000))*(cj7)*(x1804)*(x1805)))+(((sj7)*(x1809)))+(((x1811)*(x1813)))+(((x1806)*(x1811)))+(((IkReal(-1.00000000000000))*(cj7)*(x1803)*(x1804)))+(((r12)*(x1810))));
8059 evalcond[5]=((((IkReal(-1.00000000000000))*(sj5)*(x1816)))+(((cj8)*(r10)*(x1810)))+(((cj6)*(x1815)))+(((IkReal(-1.00000000000000))*(x1808)*(x1809)))+(((IkReal(-1.00000000000000))*(sj7)*(x1803)*(x1804)))+(((cj8)*(sj7)*(x1806)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x1808)))+(((IkReal(-1.00000000000000))*(sj7)*(x1804)*(x1805))));
8060 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
8061 {
8062 continue;
8063 }
8064 }
8065 
8066 {
8067 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8068 vinfos[0].jointtype = 1;
8069 vinfos[0].foffset = j3;
8070 vinfos[0].indices[0] = _ij3[0];
8071 vinfos[0].indices[1] = _ij3[1];
8072 vinfos[0].maxsolutions = _nj3;
8073 vinfos[1].jointtype = 1;
8074 vinfos[1].foffset = j4;
8075 vinfos[1].indices[0] = _ij4[0];
8076 vinfos[1].indices[1] = _ij4[1];
8077 vinfos[1].maxsolutions = _nj4;
8078 vinfos[2].jointtype = 1;
8079 vinfos[2].foffset = j5;
8080 vinfos[2].indices[0] = _ij5[0];
8081 vinfos[2].indices[1] = _ij5[1];
8082 vinfos[2].maxsolutions = _nj5;
8083 vinfos[3].jointtype = 1;
8084 vinfos[3].foffset = j6;
8085 vinfos[3].indices[0] = _ij6[0];
8086 vinfos[3].indices[1] = _ij6[1];
8087 vinfos[3].maxsolutions = _nj6;
8088 vinfos[4].jointtype = 1;
8089 vinfos[4].foffset = j7;
8090 vinfos[4].indices[0] = _ij7[0];
8091 vinfos[4].indices[1] = _ij7[1];
8092 vinfos[4].maxsolutions = _nj7;
8093 vinfos[5].jointtype = 1;
8094 vinfos[5].foffset = j8;
8095 vinfos[5].indices[0] = _ij8[0];
8096 vinfos[5].indices[1] = _ij8[1];
8097 vinfos[5].maxsolutions = _nj8;
8098 std::vector<int> vfree(0);
8099 solutions.AddSolution(vinfos,vfree);
8100 }
8101 }
8102 }
8103 
8104 }
8105 
8106 }
8107 }
8108 }
8109 
8110 }
8111 
8112 }
8113 
8114 } else
8115 {
8116 {
8117 IkReal j4array[1], cj4array[1], sj4array[1];
8118 bool j4valid[1]={false};
8119 _nj4 = 1;
8120 IkReal x1819=((r21)*(sj8));
8121 IkReal x1820=((IkReal(1.00000000000000))*(r22));
8122 IkReal x1821=((cj5)*(sj7));
8123 IkReal x1822=((cj6)*(cj7));
8124 IkReal x1823=((sj5)*(sj7));
8125 IkReal x1824=((cj5)*(cj8)*(r20));
8126 IkReal x1825=((IkReal(1.00000000000000))*(x1822));
8127 IkReal x1826=((cj8)*(r20)*(sj5));
8128 if( IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(x1819)*(x1821)))+(((x1822)*(x1826)))+(((cj8)*(r20)*(x1821)))+(((IkReal(-1.00000000000000))*(sj5)*(x1819)*(x1825)))+(((cj6)*(r22)*(x1823)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x1820))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(x1819)*(x1823)))+(((cj5)*(x1819)*(x1822)))+(((IkReal(-1.00000000000000))*(cj6)*(x1820)*(x1821)))+(((cj8)*(r20)*(x1823)))+(((IkReal(-1.00000000000000))*(x1824)*(x1825)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x1820))))))) < IKFAST_ATAN2_MAGTHRESH )
8129  continue;
8130 j4array[0]=IKatan2(((gconst5)*(((((IkReal(-1.00000000000000))*(x1819)*(x1821)))+(((x1822)*(x1826)))+(((cj8)*(r20)*(x1821)))+(((IkReal(-1.00000000000000))*(sj5)*(x1819)*(x1825)))+(((cj6)*(r22)*(x1823)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x1820)))))), ((gconst5)*(((((IkReal(-1.00000000000000))*(x1819)*(x1823)))+(((cj5)*(x1819)*(x1822)))+(((IkReal(-1.00000000000000))*(cj6)*(x1820)*(x1821)))+(((cj8)*(r20)*(x1823)))+(((IkReal(-1.00000000000000))*(x1824)*(x1825)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x1820)))))));
8131 sj4array[0]=IKsin(j4array[0]);
8132 cj4array[0]=IKcos(j4array[0]);
8133 if( j4array[0] > IKPI )
8134 {
8135  j4array[0]-=IK2PI;
8136 }
8137 else if( j4array[0] < -IKPI )
8138 { j4array[0]+=IK2PI;
8139 }
8140 j4valid[0] = true;
8141 for(int ij4 = 0; ij4 < 1; ++ij4)
8142 {
8143 if( !j4valid[ij4] )
8144 {
8145  continue;
8146 }
8147 _ij4[0] = ij4; _ij4[1] = -1;
8148 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
8149 {
8150 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
8151 {
8152  j4valid[iij4]=false; _ij4[1] = iij4; break;
8153 }
8154 }
8155 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
8156 {
8157 IkReal evalcond[3];
8158 IkReal x1827=IKsin(j4);
8159 IkReal x1828=IKcos(j4);
8160 IkReal x1829=((IkReal(1.00000000000000))*(cj5));
8161 IkReal x1830=((r21)*(sj8));
8162 IkReal x1831=((IkReal(1.00000000000000))*(cj8)*(r20));
8163 IkReal x1832=((sj5)*(x1828));
8164 evalcond[0]=((((IkReal(-1.00000000000000))*(sj6)*(x1832)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(sj6)*(x1827)*(x1829)))+(((r20)*(sj8))));
8165 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(x1831)))+(((cj7)*(x1830)))+(((IkReal(-1.00000000000000))*(x1828)*(x1829)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((sj5)*(x1827))));
8166 evalcond[2]=((((cj6)*(x1832)))+(((sj7)*(x1830)))+(((cj5)*(cj6)*(x1827)))+(((IkReal(-1.00000000000000))*(sj7)*(x1831)))+(((cj7)*(r22))));
8167 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
8168 {
8169 continue;
8170 }
8171 }
8172 
8173 {
8174 IkReal dummyeval[1];
8175 IkReal gconst16;
8176 IkReal x1833=(sj8)*(sj8);
8177 IkReal x1834=(cj8)*(cj8);
8178 IkReal x1835=((r00)*(r11));
8179 IkReal x1836=((r02)*(sj7));
8180 IkReal x1837=((cj7)*(x1834));
8181 IkReal x1838=((IkReal(1.00000000000000))*(r12)*(sj7));
8182 IkReal x1839=((IkReal(1.00000000000000))*(r01)*(r10));
8183 IkReal x1840=((cj7)*(x1833));
8184 gconst16=IKsign(((((IkReal(-1.00000000000000))*(x1837)*(x1839)))+(((IkReal(-1.00000000000000))*(x1839)*(x1840)))+(((x1835)*(x1837)))+(((cj8)*(r11)*(x1836)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1838)))+(((r10)*(sj8)*(x1836)))+(((x1835)*(x1840)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1838)))));
8185 IkReal x1841=(sj8)*(sj8);
8186 IkReal x1842=(cj8)*(cj8);
8187 IkReal x1843=((r00)*(r11));
8188 IkReal x1844=((r02)*(sj7));
8189 IkReal x1845=((cj7)*(x1842));
8190 IkReal x1846=((IkReal(1.00000000000000))*(r12)*(sj7));
8191 IkReal x1847=((IkReal(1.00000000000000))*(r01)*(r10));
8192 IkReal x1848=((cj7)*(x1841));
8193 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1846)))+(((IkReal(-1.00000000000000))*(x1845)*(x1847)))+(((cj8)*(r11)*(x1844)))+(((IkReal(-1.00000000000000))*(x1847)*(x1848)))+(((x1843)*(x1848)))+(((x1843)*(x1845)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1846)))+(((r10)*(sj8)*(x1844))));
8194 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8195 {
8196 {
8197 IkReal dummyeval[1];
8198 IkReal gconst17;
8199 IkReal x1849=(sj8)*(sj8);
8200 IkReal x1850=(cj8)*(cj8);
8201 IkReal x1851=((IkReal(1.00000000000000))*(r10));
8202 IkReal x1852=((cj7)*(sj8));
8203 IkReal x1853=((r00)*(r11));
8204 IkReal x1854=((cj7)*(cj8));
8205 IkReal x1855=((sj7)*(x1849));
8206 IkReal x1856=((sj7)*(x1850));
8207 gconst17=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x1851)*(x1856)))+(((IkReal(-1.00000000000000))*(r01)*(x1851)*(x1855)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1854)))+(((IkReal(-1.00000000000000))*(r02)*(x1851)*(x1852)))+(((x1853)*(x1855)))+(((x1853)*(x1856)))+(((r01)*(r12)*(x1854)))+(((r00)*(r12)*(x1852)))));
8208 IkReal x1857=(sj8)*(sj8);
8209 IkReal x1858=(cj8)*(cj8);
8210 IkReal x1859=((IkReal(1.00000000000000))*(r10));
8211 IkReal x1860=((cj7)*(sj8));
8212 IkReal x1861=((r00)*(r11));
8213 IkReal x1862=((cj7)*(cj8));
8214 IkReal x1863=((sj7)*(x1857));
8215 IkReal x1864=((sj7)*(x1858));
8216 dummyeval[0]=((((r01)*(r12)*(x1862)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1862)))+(((r00)*(r12)*(x1860)))+(((IkReal(-1.00000000000000))*(r01)*(x1859)*(x1863)))+(((IkReal(-1.00000000000000))*(r01)*(x1859)*(x1864)))+(((x1861)*(x1863)))+(((x1861)*(x1864)))+(((IkReal(-1.00000000000000))*(r02)*(x1859)*(x1860))));
8217 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8218 {
8219 continue;
8220 
8221 } else
8222 {
8223 {
8224 IkReal j3array[1], cj3array[1], sj3array[1];
8225 bool j3valid[1]={false};
8226 _nj3 = 1;
8227 IkReal x1865=((cj6)*(sj7));
8228 IkReal x1866=((IkReal(1.00000000000000))*(sj8));
8229 IkReal x1867=((cj8)*(sj6));
8230 IkReal x1868=((sj6)*(sj8));
8231 IkReal x1869=((IkReal(1.00000000000000))*(cj6)*(cj7));
8232 if( IKabs(((gconst17)*(((((IkReal(-1.00000000000000))*(r11)*(x1865)*(x1866)))+(((r11)*(x1867)))+(((IkReal(-1.00000000000000))*(r12)*(x1869)))+(((r10)*(x1868)))+(((cj8)*(r10)*(x1865))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((IkReal(-1.00000000000000))*(r01)*(x1865)*(x1866)))+(((IkReal(-1.00000000000000))*(r02)*(x1869)))+(((r01)*(x1867)))+(((cj8)*(r00)*(x1865)))+(((r00)*(x1868))))))) < IKFAST_ATAN2_MAGTHRESH )
8233  continue;
8234 j3array[0]=IKatan2(((gconst17)*(((((IkReal(-1.00000000000000))*(r11)*(x1865)*(x1866)))+(((r11)*(x1867)))+(((IkReal(-1.00000000000000))*(r12)*(x1869)))+(((r10)*(x1868)))+(((cj8)*(r10)*(x1865)))))), ((gconst17)*(((((IkReal(-1.00000000000000))*(r01)*(x1865)*(x1866)))+(((IkReal(-1.00000000000000))*(r02)*(x1869)))+(((r01)*(x1867)))+(((cj8)*(r00)*(x1865)))+(((r00)*(x1868)))))));
8235 sj3array[0]=IKsin(j3array[0]);
8236 cj3array[0]=IKcos(j3array[0]);
8237 if( j3array[0] > IKPI )
8238 {
8239  j3array[0]-=IK2PI;
8240 }
8241 else if( j3array[0] < -IKPI )
8242 { j3array[0]+=IK2PI;
8243 }
8244 j3valid[0] = true;
8245 for(int ij3 = 0; ij3 < 1; ++ij3)
8246 {
8247 if( !j3valid[ij3] )
8248 {
8249  continue;
8250 }
8251 _ij3[0] = ij3; _ij3[1] = -1;
8252 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8253 {
8254 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8255 {
8256  j3valid[iij3]=false; _ij3[1] = iij3; break;
8257 }
8258 }
8259 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8260 {
8261 IkReal evalcond[6];
8262 IkReal x1870=IKsin(j3);
8263 IkReal x1871=IKcos(j3);
8264 IkReal x1872=((cj4)*(cj5));
8265 IkReal x1873=((r01)*(sj8));
8266 IkReal x1874=((cj8)*(r00));
8267 IkReal x1875=((r00)*(sj8));
8268 IkReal x1876=((cj8)*(r11));
8269 IkReal x1877=((r11)*(sj8));
8270 IkReal x1878=((sj4)*(sj5));
8271 IkReal x1879=((r10)*(sj8));
8272 IkReal x1880=((cj8)*(r10));
8273 IkReal x1881=((cj7)*(x1870));
8274 IkReal x1882=((sj7)*(x1871));
8275 IkReal x1883=((IkReal(1.00000000000000))*(x1870));
8276 IkReal x1884=((IkReal(1.00000000000000))*(x1871));
8277 IkReal x1885=((cj8)*(x1870));
8278 IkReal x1886=((IkReal(1.00000000000000))*(x1877));
8279 IkReal x1887=((sj7)*(x1870));
8280 IkReal x1888=((cj7)*(x1871));
8281 evalcond[0]=((((IkReal(-1.00000000000000))*(x1876)*(x1884)))+(((IkReal(-1.00000000000000))*(x1879)*(x1884)))+(cj6)+(((r01)*(x1885)))+(((x1870)*(x1875))));
8282 evalcond[1]=((((sj6)*(x1878)))+(((IkReal(-1.00000000000000))*(x1876)*(x1883)))+(((IkReal(-1.00000000000000))*(x1879)*(x1883)))+(((IkReal(-1.00000000000000))*(sj6)*(x1872)))+(((IkReal(-1.00000000000000))*(x1875)*(x1884)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1884))));
8283 evalcond[2]=((((r12)*(x1882)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1883)))+(((x1880)*(x1888)))+(((IkReal(-1.00000000000000))*(x1874)*(x1881)))+(((IkReal(-1.00000000000000))*(cj7)*(x1877)*(x1884)))+(((x1873)*(x1881))));
8284 evalcond[3]=((((IkReal(-1.00000000000000))*(x1882)*(x1886)))+(sj6)+(((x1880)*(x1882)))+(((x1873)*(x1887)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1884)))+(((IkReal(-1.00000000000000))*(sj7)*(x1874)*(x1883)))+(((r02)*(x1881))));
8285 evalcond[4]=((((x1874)*(x1888)))+(((r12)*(x1887)))+(((x1880)*(x1881)))+(((cj5)*(sj4)))+(((cj4)*(sj5)))+(((IkReal(-1.00000000000000))*(x1881)*(x1886)))+(((IkReal(-1.00000000000000))*(cj7)*(x1873)*(x1884)))+(((r02)*(x1882))));
8286 evalcond[5]=((((IkReal(-1.00000000000000))*(x1873)*(x1882)))+(((IkReal(-1.00000000000000))*(sj7)*(x1877)*(x1883)))+(((x1874)*(x1882)))+(((IkReal(-1.00000000000000))*(cj6)*(x1878)))+(((x1880)*(x1887)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1884)))+(((cj6)*(x1872)))+(((IkReal(-1.00000000000000))*(r12)*(x1881))));
8287 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
8288 {
8289 continue;
8290 }
8291 }
8292 
8293 {
8294 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8295 vinfos[0].jointtype = 1;
8296 vinfos[0].foffset = j3;
8297 vinfos[0].indices[0] = _ij3[0];
8298 vinfos[0].indices[1] = _ij3[1];
8299 vinfos[0].maxsolutions = _nj3;
8300 vinfos[1].jointtype = 1;
8301 vinfos[1].foffset = j4;
8302 vinfos[1].indices[0] = _ij4[0];
8303 vinfos[1].indices[1] = _ij4[1];
8304 vinfos[1].maxsolutions = _nj4;
8305 vinfos[2].jointtype = 1;
8306 vinfos[2].foffset = j5;
8307 vinfos[2].indices[0] = _ij5[0];
8308 vinfos[2].indices[1] = _ij5[1];
8309 vinfos[2].maxsolutions = _nj5;
8310 vinfos[3].jointtype = 1;
8311 vinfos[3].foffset = j6;
8312 vinfos[3].indices[0] = _ij6[0];
8313 vinfos[3].indices[1] = _ij6[1];
8314 vinfos[3].maxsolutions = _nj6;
8315 vinfos[4].jointtype = 1;
8316 vinfos[4].foffset = j7;
8317 vinfos[4].indices[0] = _ij7[0];
8318 vinfos[4].indices[1] = _ij7[1];
8319 vinfos[4].maxsolutions = _nj7;
8320 vinfos[5].jointtype = 1;
8321 vinfos[5].foffset = j8;
8322 vinfos[5].indices[0] = _ij8[0];
8323 vinfos[5].indices[1] = _ij8[1];
8324 vinfos[5].maxsolutions = _nj8;
8325 std::vector<int> vfree(0);
8326 solutions.AddSolution(vinfos,vfree);
8327 }
8328 }
8329 }
8330 
8331 }
8332 
8333 }
8334 
8335 } else
8336 {
8337 {
8338 IkReal j3array[1], cj3array[1], sj3array[1];
8339 bool j3valid[1]={false};
8340 _nj3 = 1;
8341 IkReal x1889=((cj6)*(cj7));
8342 IkReal x1890=((IkReal(1.00000000000000))*(sj8));
8343 IkReal x1891=((cj6)*(sj7));
8344 if( IKabs(((gconst16)*(((((cj8)*(r10)*(x1889)))+(((IkReal(-1.00000000000000))*(r11)*(x1889)*(x1890)))+(((r12)*(x1891))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((r02)*(x1891)))+(((cj8)*(r00)*(x1889)))+(((IkReal(-1.00000000000000))*(r01)*(x1889)*(x1890))))))) < IKFAST_ATAN2_MAGTHRESH )
8345  continue;
8346 j3array[0]=IKatan2(((gconst16)*(((((cj8)*(r10)*(x1889)))+(((IkReal(-1.00000000000000))*(r11)*(x1889)*(x1890)))+(((r12)*(x1891)))))), ((gconst16)*(((((r02)*(x1891)))+(((cj8)*(r00)*(x1889)))+(((IkReal(-1.00000000000000))*(r01)*(x1889)*(x1890)))))));
8347 sj3array[0]=IKsin(j3array[0]);
8348 cj3array[0]=IKcos(j3array[0]);
8349 if( j3array[0] > IKPI )
8350 {
8351  j3array[0]-=IK2PI;
8352 }
8353 else if( j3array[0] < -IKPI )
8354 { j3array[0]+=IK2PI;
8355 }
8356 j3valid[0] = true;
8357 for(int ij3 = 0; ij3 < 1; ++ij3)
8358 {
8359 if( !j3valid[ij3] )
8360 {
8361  continue;
8362 }
8363 _ij3[0] = ij3; _ij3[1] = -1;
8364 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8365 {
8366 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8367 {
8368  j3valid[iij3]=false; _ij3[1] = iij3; break;
8369 }
8370 }
8371 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8372 {
8373 IkReal evalcond[6];
8374 IkReal x1892=IKsin(j3);
8375 IkReal x1893=IKcos(j3);
8376 IkReal x1894=((cj4)*(cj5));
8377 IkReal x1895=((r01)*(sj8));
8378 IkReal x1896=((cj8)*(r00));
8379 IkReal x1897=((r00)*(sj8));
8380 IkReal x1898=((cj8)*(r11));
8381 IkReal x1899=((r11)*(sj8));
8382 IkReal x1900=((sj4)*(sj5));
8383 IkReal x1901=((r10)*(sj8));
8384 IkReal x1902=((cj8)*(r10));
8385 IkReal x1903=((cj7)*(x1892));
8386 IkReal x1904=((sj7)*(x1893));
8387 IkReal x1905=((IkReal(1.00000000000000))*(x1892));
8388 IkReal x1906=((IkReal(1.00000000000000))*(x1893));
8389 IkReal x1907=((cj8)*(x1892));
8390 IkReal x1908=((IkReal(1.00000000000000))*(x1899));
8391 IkReal x1909=((sj7)*(x1892));
8392 IkReal x1910=((cj7)*(x1893));
8393 evalcond[0]=((((r01)*(x1907)))+(cj6)+(((x1892)*(x1897)))+(((IkReal(-1.00000000000000))*(x1901)*(x1906)))+(((IkReal(-1.00000000000000))*(x1898)*(x1906))));
8394 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1906)))+(((IkReal(-1.00000000000000))*(x1901)*(x1905)))+(((IkReal(-1.00000000000000))*(x1898)*(x1905)))+(((IkReal(-1.00000000000000))*(x1897)*(x1906)))+(((sj6)*(x1900)))+(((IkReal(-1.00000000000000))*(sj6)*(x1894))));
8395 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1905)))+(((IkReal(-1.00000000000000))*(cj7)*(x1899)*(x1906)))+(((r12)*(x1904)))+(((IkReal(-1.00000000000000))*(x1896)*(x1903)))+(((x1895)*(x1903)))+(((x1902)*(x1910))));
8396 evalcond[3]=((sj6)+(((IkReal(-1.00000000000000))*(x1904)*(x1908)))+(((x1895)*(x1909)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1906)))+(((x1902)*(x1904)))+(((r02)*(x1903)))+(((IkReal(-1.00000000000000))*(sj7)*(x1896)*(x1905))));
8397 evalcond[4]=((((IkReal(-1.00000000000000))*(x1903)*(x1908)))+(((cj5)*(sj4)))+(((r12)*(x1909)))+(((cj4)*(sj5)))+(((IkReal(-1.00000000000000))*(cj7)*(x1895)*(x1906)))+(((x1896)*(x1910)))+(((x1902)*(x1903)))+(((r02)*(x1904))));
8398 evalcond[5]=((((IkReal(-1.00000000000000))*(x1895)*(x1904)))+(((IkReal(-1.00000000000000))*(sj7)*(x1899)*(x1905)))+(((IkReal(-1.00000000000000))*(r12)*(x1903)))+(((cj6)*(x1894)))+(((IkReal(-1.00000000000000))*(cj6)*(x1900)))+(((x1902)*(x1909)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1906)))+(((x1896)*(x1904))));
8399 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
8400 {
8401 continue;
8402 }
8403 }
8404 
8405 {
8406 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8407 vinfos[0].jointtype = 1;
8408 vinfos[0].foffset = j3;
8409 vinfos[0].indices[0] = _ij3[0];
8410 vinfos[0].indices[1] = _ij3[1];
8411 vinfos[0].maxsolutions = _nj3;
8412 vinfos[1].jointtype = 1;
8413 vinfos[1].foffset = j4;
8414 vinfos[1].indices[0] = _ij4[0];
8415 vinfos[1].indices[1] = _ij4[1];
8416 vinfos[1].maxsolutions = _nj4;
8417 vinfos[2].jointtype = 1;
8418 vinfos[2].foffset = j5;
8419 vinfos[2].indices[0] = _ij5[0];
8420 vinfos[2].indices[1] = _ij5[1];
8421 vinfos[2].maxsolutions = _nj5;
8422 vinfos[3].jointtype = 1;
8423 vinfos[3].foffset = j6;
8424 vinfos[3].indices[0] = _ij6[0];
8425 vinfos[3].indices[1] = _ij6[1];
8426 vinfos[3].maxsolutions = _nj6;
8427 vinfos[4].jointtype = 1;
8428 vinfos[4].foffset = j7;
8429 vinfos[4].indices[0] = _ij7[0];
8430 vinfos[4].indices[1] = _ij7[1];
8431 vinfos[4].maxsolutions = _nj7;
8432 vinfos[5].jointtype = 1;
8433 vinfos[5].foffset = j8;
8434 vinfos[5].indices[0] = _ij8[0];
8435 vinfos[5].indices[1] = _ij8[1];
8436 vinfos[5].maxsolutions = _nj8;
8437 std::vector<int> vfree(0);
8438 solutions.AddSolution(vinfos,vfree);
8439 }
8440 }
8441 }
8442 
8443 }
8444 
8445 }
8446 }
8447 }
8448 
8449 }
8450 
8451 }
8452 
8453 } else
8454 {
8455 {
8456 IkReal j4array[1], cj4array[1], sj4array[1];
8457 bool j4valid[1]={false};
8458 _nj4 = 1;
8459 IkReal x1911=((sj5)*(sj6));
8460 IkReal x1912=((r22)*(sj7));
8461 IkReal x1913=((cj8)*(r21));
8462 IkReal x1914=((r20)*(sj8));
8463 IkReal x1915=((cj5)*(sj6));
8464 IkReal x1916=((cj7)*(cj8)*(r20));
8465 IkReal x1917=((cj7)*(r21)*(sj8));
8466 if( IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(x1911)*(x1917)))+(((x1911)*(x1916)))+(((x1911)*(x1912)))+(((cj5)*(x1913)))+(((cj5)*(x1914))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((sj5)*(x1913)))+(((sj5)*(x1914)))+(((IkReal(-1.00000000000000))*(x1912)*(x1915)))+(((IkReal(-1.00000000000000))*(x1915)*(x1916)))+(((x1915)*(x1917))))))) < IKFAST_ATAN2_MAGTHRESH )
8467  continue;
8468 j4array[0]=IKatan2(((gconst4)*(((((IkReal(-1.00000000000000))*(x1911)*(x1917)))+(((x1911)*(x1916)))+(((x1911)*(x1912)))+(((cj5)*(x1913)))+(((cj5)*(x1914)))))), ((gconst4)*(((((sj5)*(x1913)))+(((sj5)*(x1914)))+(((IkReal(-1.00000000000000))*(x1912)*(x1915)))+(((IkReal(-1.00000000000000))*(x1915)*(x1916)))+(((x1915)*(x1917)))))));
8469 sj4array[0]=IKsin(j4array[0]);
8470 cj4array[0]=IKcos(j4array[0]);
8471 if( j4array[0] > IKPI )
8472 {
8473  j4array[0]-=IK2PI;
8474 }
8475 else if( j4array[0] < -IKPI )
8476 { j4array[0]+=IK2PI;
8477 }
8478 j4valid[0] = true;
8479 for(int ij4 = 0; ij4 < 1; ++ij4)
8480 {
8481 if( !j4valid[ij4] )
8482 {
8483  continue;
8484 }
8485 _ij4[0] = ij4; _ij4[1] = -1;
8486 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
8487 {
8488 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
8489 {
8490  j4valid[iij4]=false; _ij4[1] = iij4; break;
8491 }
8492 }
8493 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
8494 {
8495 IkReal evalcond[3];
8496 IkReal x1918=IKsin(j4);
8497 IkReal x1919=IKcos(j4);
8498 IkReal x1920=((IkReal(1.00000000000000))*(cj5));
8499 IkReal x1921=((r21)*(sj8));
8500 IkReal x1922=((IkReal(1.00000000000000))*(cj8)*(r20));
8501 IkReal x1923=((sj5)*(x1919));
8502 evalcond[0]=((((cj8)*(r21)))+(((r20)*(sj8)))+(((IkReal(-1.00000000000000))*(sj6)*(x1923)))+(((IkReal(-1.00000000000000))*(sj6)*(x1918)*(x1920))));
8503 evalcond[1]=((((sj5)*(x1918)))+(((cj7)*(x1921)))+(((IkReal(-1.00000000000000))*(cj7)*(x1922)))+(((IkReal(-1.00000000000000))*(x1919)*(x1920)))+(((IkReal(-1.00000000000000))*(r22)*(sj7))));
8504 evalcond[2]=((((sj7)*(x1921)))+(((cj5)*(cj6)*(x1918)))+(((IkReal(-1.00000000000000))*(sj7)*(x1922)))+(((cj6)*(x1923)))+(((cj7)*(r22))));
8505 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
8506 {
8507 continue;
8508 }
8509 }
8510 
8511 {
8512 IkReal dummyeval[1];
8513 IkReal gconst16;
8514 IkReal x1924=(sj8)*(sj8);
8515 IkReal x1925=(cj8)*(cj8);
8516 IkReal x1926=((r00)*(r11));
8517 IkReal x1927=((r02)*(sj7));
8518 IkReal x1928=((cj7)*(x1925));
8519 IkReal x1929=((IkReal(1.00000000000000))*(r12)*(sj7));
8520 IkReal x1930=((IkReal(1.00000000000000))*(r01)*(r10));
8521 IkReal x1931=((cj7)*(x1924));
8522 gconst16=IKsign(((((IkReal(-1.00000000000000))*(x1928)*(x1930)))+(((IkReal(-1.00000000000000))*(x1930)*(x1931)))+(((cj8)*(r11)*(x1927)))+(((r10)*(sj8)*(x1927)))+(((x1926)*(x1931)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1929)))+(((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1929)))+(((x1926)*(x1928)))));
8523 IkReal x1932=(sj8)*(sj8);
8524 IkReal x1933=(cj8)*(cj8);
8525 IkReal x1934=((r00)*(r11));
8526 IkReal x1935=((r02)*(sj7));
8527 IkReal x1936=((cj7)*(x1933));
8528 IkReal x1937=((IkReal(1.00000000000000))*(r12)*(sj7));
8529 IkReal x1938=((IkReal(1.00000000000000))*(r01)*(r10));
8530 IkReal x1939=((cj7)*(x1932));
8531 dummyeval[0]=((((IkReal(-1.00000000000000))*(r00)*(sj8)*(x1937)))+(((x1934)*(x1936)))+(((x1934)*(x1939)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1937)))+(((IkReal(-1.00000000000000))*(x1938)*(x1939)))+(((cj8)*(r11)*(x1935)))+(((IkReal(-1.00000000000000))*(x1936)*(x1938)))+(((r10)*(sj8)*(x1935))));
8532 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8533 {
8534 {
8535 IkReal dummyeval[1];
8536 IkReal gconst17;
8537 IkReal x1940=(sj8)*(sj8);
8538 IkReal x1941=(cj8)*(cj8);
8539 IkReal x1942=((IkReal(1.00000000000000))*(r10));
8540 IkReal x1943=((cj7)*(sj8));
8541 IkReal x1944=((r00)*(r11));
8542 IkReal x1945=((cj7)*(cj8));
8543 IkReal x1946=((sj7)*(x1940));
8544 IkReal x1947=((sj7)*(x1941));
8545 gconst17=IKsign(((((IkReal(-1.00000000000000))*(r02)*(r11)*(x1945)))+(((x1944)*(x1947)))+(((x1944)*(x1946)))+(((IkReal(-1.00000000000000))*(r01)*(x1942)*(x1946)))+(((IkReal(-1.00000000000000))*(r01)*(x1942)*(x1947)))+(((r00)*(r12)*(x1943)))+(((IkReal(-1.00000000000000))*(r02)*(x1942)*(x1943)))+(((r01)*(r12)*(x1945)))));
8546 IkReal x1948=(sj8)*(sj8);
8547 IkReal x1949=(cj8)*(cj8);
8548 IkReal x1950=((IkReal(1.00000000000000))*(r10));
8549 IkReal x1951=((cj7)*(sj8));
8550 IkReal x1952=((r00)*(r11));
8551 IkReal x1953=((cj7)*(cj8));
8552 IkReal x1954=((sj7)*(x1948));
8553 IkReal x1955=((sj7)*(x1949));
8554 dummyeval[0]=((((r01)*(r12)*(x1953)))+(((x1952)*(x1955)))+(((x1952)*(x1954)))+(((IkReal(-1.00000000000000))*(r01)*(x1950)*(x1954)))+(((IkReal(-1.00000000000000))*(r01)*(x1950)*(x1955)))+(((r00)*(r12)*(x1951)))+(((IkReal(-1.00000000000000))*(r02)*(x1950)*(x1951)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1953))));
8555 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8556 {
8557 continue;
8558 
8559 } else
8560 {
8561 {
8562 IkReal j3array[1], cj3array[1], sj3array[1];
8563 bool j3valid[1]={false};
8564 _nj3 = 1;
8565 IkReal x1956=((cj6)*(sj7));
8566 IkReal x1957=((IkReal(1.00000000000000))*(sj8));
8567 IkReal x1958=((cj8)*(sj6));
8568 IkReal x1959=((sj6)*(sj8));
8569 IkReal x1960=((IkReal(1.00000000000000))*(cj6)*(cj7));
8570 if( IKabs(((gconst17)*(((((r11)*(x1958)))+(((r10)*(x1959)))+(((IkReal(-1.00000000000000))*(r11)*(x1956)*(x1957)))+(((IkReal(-1.00000000000000))*(r12)*(x1960)))+(((cj8)*(r10)*(x1956))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((cj8)*(r00)*(x1956)))+(((IkReal(-1.00000000000000))*(r02)*(x1960)))+(((IkReal(-1.00000000000000))*(r01)*(x1956)*(x1957)))+(((r01)*(x1958)))+(((r00)*(x1959))))))) < IKFAST_ATAN2_MAGTHRESH )
8571  continue;
8572 j3array[0]=IKatan2(((gconst17)*(((((r11)*(x1958)))+(((r10)*(x1959)))+(((IkReal(-1.00000000000000))*(r11)*(x1956)*(x1957)))+(((IkReal(-1.00000000000000))*(r12)*(x1960)))+(((cj8)*(r10)*(x1956)))))), ((gconst17)*(((((cj8)*(r00)*(x1956)))+(((IkReal(-1.00000000000000))*(r02)*(x1960)))+(((IkReal(-1.00000000000000))*(r01)*(x1956)*(x1957)))+(((r01)*(x1958)))+(((r00)*(x1959)))))));
8573 sj3array[0]=IKsin(j3array[0]);
8574 cj3array[0]=IKcos(j3array[0]);
8575 if( j3array[0] > IKPI )
8576 {
8577  j3array[0]-=IK2PI;
8578 }
8579 else if( j3array[0] < -IKPI )
8580 { j3array[0]+=IK2PI;
8581 }
8582 j3valid[0] = true;
8583 for(int ij3 = 0; ij3 < 1; ++ij3)
8584 {
8585 if( !j3valid[ij3] )
8586 {
8587  continue;
8588 }
8589 _ij3[0] = ij3; _ij3[1] = -1;
8590 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8591 {
8592 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8593 {
8594  j3valid[iij3]=false; _ij3[1] = iij3; break;
8595 }
8596 }
8597 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8598 {
8599 IkReal evalcond[6];
8600 IkReal x1961=IKsin(j3);
8601 IkReal x1962=IKcos(j3);
8602 IkReal x1963=((cj4)*(cj5));
8603 IkReal x1964=((r01)*(sj8));
8604 IkReal x1965=((cj8)*(r00));
8605 IkReal x1966=((r00)*(sj8));
8606 IkReal x1967=((cj8)*(r11));
8607 IkReal x1968=((r11)*(sj8));
8608 IkReal x1969=((sj4)*(sj5));
8609 IkReal x1970=((r10)*(sj8));
8610 IkReal x1971=((cj8)*(r10));
8611 IkReal x1972=((cj7)*(x1961));
8612 IkReal x1973=((sj7)*(x1962));
8613 IkReal x1974=((IkReal(1.00000000000000))*(x1961));
8614 IkReal x1975=((IkReal(1.00000000000000))*(x1962));
8615 IkReal x1976=((cj8)*(x1961));
8616 IkReal x1977=((IkReal(1.00000000000000))*(x1968));
8617 IkReal x1978=((sj7)*(x1961));
8618 IkReal x1979=((cj7)*(x1962));
8619 evalcond[0]=((cj6)+(((IkReal(-1.00000000000000))*(x1970)*(x1975)))+(((r01)*(x1976)))+(((x1961)*(x1966)))+(((IkReal(-1.00000000000000))*(x1967)*(x1975))));
8620 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1975)))+(((IkReal(-1.00000000000000))*(sj6)*(x1963)))+(((IkReal(-1.00000000000000))*(x1966)*(x1975)))+(((IkReal(-1.00000000000000))*(x1970)*(x1974)))+(((sj6)*(x1969)))+(((IkReal(-1.00000000000000))*(x1967)*(x1974))));
8621 evalcond[2]=((((r12)*(x1973)))+(((x1964)*(x1972)))+(((x1971)*(x1979)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1974)))+(((IkReal(-1.00000000000000))*(cj7)*(x1968)*(x1975)))+(((IkReal(-1.00000000000000))*(x1965)*(x1972))));
8622 evalcond[3]=((((r02)*(x1972)))+(sj6)+(((IkReal(-1.00000000000000))*(sj7)*(x1965)*(x1974)))+(((x1964)*(x1978)))+(((x1971)*(x1973)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1975)))+(((IkReal(-1.00000000000000))*(x1973)*(x1977))));
8623 evalcond[4]=((((r02)*(x1973)))+(((IkReal(-1.00000000000000))*(cj7)*(x1964)*(x1975)))+(((r12)*(x1978)))+(((x1971)*(x1972)))+(((cj5)*(sj4)))+(((IkReal(-1.00000000000000))*(x1972)*(x1977)))+(((cj4)*(sj5)))+(((x1965)*(x1979))));
8624 evalcond[5]=((((IkReal(-1.00000000000000))*(cj6)*(x1969)))+(((cj6)*(x1963)))+(((x1971)*(x1978)))+(((IkReal(-1.00000000000000))*(x1964)*(x1973)))+(((IkReal(-1.00000000000000))*(r12)*(x1972)))+(((x1965)*(x1973)))+(((IkReal(-1.00000000000000))*(sj7)*(x1968)*(x1974)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1975))));
8625 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
8626 {
8627 continue;
8628 }
8629 }
8630 
8631 {
8632 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8633 vinfos[0].jointtype = 1;
8634 vinfos[0].foffset = j3;
8635 vinfos[0].indices[0] = _ij3[0];
8636 vinfos[0].indices[1] = _ij3[1];
8637 vinfos[0].maxsolutions = _nj3;
8638 vinfos[1].jointtype = 1;
8639 vinfos[1].foffset = j4;
8640 vinfos[1].indices[0] = _ij4[0];
8641 vinfos[1].indices[1] = _ij4[1];
8642 vinfos[1].maxsolutions = _nj4;
8643 vinfos[2].jointtype = 1;
8644 vinfos[2].foffset = j5;
8645 vinfos[2].indices[0] = _ij5[0];
8646 vinfos[2].indices[1] = _ij5[1];
8647 vinfos[2].maxsolutions = _nj5;
8648 vinfos[3].jointtype = 1;
8649 vinfos[3].foffset = j6;
8650 vinfos[3].indices[0] = _ij6[0];
8651 vinfos[3].indices[1] = _ij6[1];
8652 vinfos[3].maxsolutions = _nj6;
8653 vinfos[4].jointtype = 1;
8654 vinfos[4].foffset = j7;
8655 vinfos[4].indices[0] = _ij7[0];
8656 vinfos[4].indices[1] = _ij7[1];
8657 vinfos[4].maxsolutions = _nj7;
8658 vinfos[5].jointtype = 1;
8659 vinfos[5].foffset = j8;
8660 vinfos[5].indices[0] = _ij8[0];
8661 vinfos[5].indices[1] = _ij8[1];
8662 vinfos[5].maxsolutions = _nj8;
8663 std::vector<int> vfree(0);
8664 solutions.AddSolution(vinfos,vfree);
8665 }
8666 }
8667 }
8668 
8669 }
8670 
8671 }
8672 
8673 } else
8674 {
8675 {
8676 IkReal j3array[1], cj3array[1], sj3array[1];
8677 bool j3valid[1]={false};
8678 _nj3 = 1;
8679 IkReal x1980=((cj6)*(cj7));
8680 IkReal x1981=((IkReal(1.00000000000000))*(sj8));
8681 IkReal x1982=((cj6)*(sj7));
8682 if( IKabs(((gconst16)*(((((cj8)*(r10)*(x1980)))+(((r12)*(x1982)))+(((IkReal(-1.00000000000000))*(r11)*(x1980)*(x1981))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((cj8)*(r00)*(x1980)))+(((IkReal(-1.00000000000000))*(r01)*(x1980)*(x1981)))+(((r02)*(x1982))))))) < IKFAST_ATAN2_MAGTHRESH )
8683  continue;
8684 j3array[0]=IKatan2(((gconst16)*(((((cj8)*(r10)*(x1980)))+(((r12)*(x1982)))+(((IkReal(-1.00000000000000))*(r11)*(x1980)*(x1981)))))), ((gconst16)*(((((cj8)*(r00)*(x1980)))+(((IkReal(-1.00000000000000))*(r01)*(x1980)*(x1981)))+(((r02)*(x1982)))))));
8685 sj3array[0]=IKsin(j3array[0]);
8686 cj3array[0]=IKcos(j3array[0]);
8687 if( j3array[0] > IKPI )
8688 {
8689  j3array[0]-=IK2PI;
8690 }
8691 else if( j3array[0] < -IKPI )
8692 { j3array[0]+=IK2PI;
8693 }
8694 j3valid[0] = true;
8695 for(int ij3 = 0; ij3 < 1; ++ij3)
8696 {
8697 if( !j3valid[ij3] )
8698 {
8699  continue;
8700 }
8701 _ij3[0] = ij3; _ij3[1] = -1;
8702 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8703 {
8704 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8705 {
8706  j3valid[iij3]=false; _ij3[1] = iij3; break;
8707 }
8708 }
8709 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8710 {
8711 IkReal evalcond[6];
8712 IkReal x1983=IKsin(j3);
8713 IkReal x1984=IKcos(j3);
8714 IkReal x1985=((cj4)*(cj5));
8715 IkReal x1986=((r01)*(sj8));
8716 IkReal x1987=((cj8)*(r00));
8717 IkReal x1988=((r00)*(sj8));
8718 IkReal x1989=((cj8)*(r11));
8719 IkReal x1990=((r11)*(sj8));
8720 IkReal x1991=((sj4)*(sj5));
8721 IkReal x1992=((r10)*(sj8));
8722 IkReal x1993=((cj8)*(r10));
8723 IkReal x1994=((cj7)*(x1983));
8724 IkReal x1995=((sj7)*(x1984));
8725 IkReal x1996=((IkReal(1.00000000000000))*(x1983));
8726 IkReal x1997=((IkReal(1.00000000000000))*(x1984));
8727 IkReal x1998=((cj8)*(x1983));
8728 IkReal x1999=((IkReal(1.00000000000000))*(x1990));
8729 IkReal x2000=((sj7)*(x1983));
8730 IkReal x2001=((cj7)*(x1984));
8731 evalcond[0]=((cj6)+(((IkReal(-1.00000000000000))*(x1989)*(x1997)))+(((IkReal(-1.00000000000000))*(x1992)*(x1997)))+(((r01)*(x1998)))+(((x1983)*(x1988))));
8732 evalcond[1]=((((IkReal(-1.00000000000000))*(sj6)*(x1985)))+(((IkReal(-1.00000000000000))*(x1989)*(x1996)))+(((IkReal(-1.00000000000000))*(cj8)*(r01)*(x1997)))+(((sj6)*(x1991)))+(((IkReal(-1.00000000000000))*(x1992)*(x1996)))+(((IkReal(-1.00000000000000))*(x1988)*(x1997))));
8733 evalcond[2]=((((IkReal(-1.00000000000000))*(x1987)*(x1994)))+(((r12)*(x1995)))+(((x1993)*(x2001)))+(((x1986)*(x1994)))+(((IkReal(-1.00000000000000))*(cj7)*(x1990)*(x1997)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x1996))));
8734 evalcond[3]=((sj6)+(((x1986)*(x2000)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x1997)))+(((IkReal(-1.00000000000000))*(sj7)*(x1987)*(x1996)))+(((r02)*(x1994)))+(((IkReal(-1.00000000000000))*(x1995)*(x1999)))+(((x1993)*(x1995))));
8735 evalcond[4]=((((r12)*(x2000)))+(((x1987)*(x2001)))+(((cj5)*(sj4)))+(((r02)*(x1995)))+(((cj4)*(sj5)))+(((IkReal(-1.00000000000000))*(cj7)*(x1986)*(x1997)))+(((IkReal(-1.00000000000000))*(x1994)*(x1999)))+(((x1993)*(x1994))));
8736 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x1994)))+(((IkReal(-1.00000000000000))*(cj6)*(x1991)))+(((x1993)*(x2000)))+(((cj6)*(x1985)))+(((IkReal(-1.00000000000000))*(cj7)*(r02)*(x1997)))+(((IkReal(-1.00000000000000))*(x1986)*(x1995)))+(((x1987)*(x1995)))+(((IkReal(-1.00000000000000))*(sj7)*(x1990)*(x1996))));
8737 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
8738 {
8739 continue;
8740 }
8741 }
8742 
8743 {
8744 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8745 vinfos[0].jointtype = 1;
8746 vinfos[0].foffset = j3;
8747 vinfos[0].indices[0] = _ij3[0];
8748 vinfos[0].indices[1] = _ij3[1];
8749 vinfos[0].maxsolutions = _nj3;
8750 vinfos[1].jointtype = 1;
8751 vinfos[1].foffset = j4;
8752 vinfos[1].indices[0] = _ij4[0];
8753 vinfos[1].indices[1] = _ij4[1];
8754 vinfos[1].maxsolutions = _nj4;
8755 vinfos[2].jointtype = 1;
8756 vinfos[2].foffset = j5;
8757 vinfos[2].indices[0] = _ij5[0];
8758 vinfos[2].indices[1] = _ij5[1];
8759 vinfos[2].maxsolutions = _nj5;
8760 vinfos[3].jointtype = 1;
8761 vinfos[3].foffset = j6;
8762 vinfos[3].indices[0] = _ij6[0];
8763 vinfos[3].indices[1] = _ij6[1];
8764 vinfos[3].maxsolutions = _nj6;
8765 vinfos[4].jointtype = 1;
8766 vinfos[4].foffset = j7;
8767 vinfos[4].indices[0] = _ij7[0];
8768 vinfos[4].indices[1] = _ij7[1];
8769 vinfos[4].maxsolutions = _nj7;
8770 vinfos[5].jointtype = 1;
8771 vinfos[5].foffset = j8;
8772 vinfos[5].indices[0] = _ij8[0];
8773 vinfos[5].indices[1] = _ij8[1];
8774 vinfos[5].maxsolutions = _nj8;
8775 std::vector<int> vfree(0);
8776 solutions.AddSolution(vinfos,vfree);
8777 }
8778 }
8779 }
8780 
8781 }
8782 
8783 }
8784 }
8785 }
8786 
8787 }
8788 
8789 }
8790 }
8791 }
8792 
8793 }
8794 
8795 }
8796 
8797 } else
8798 {
8799 {
8800 IkReal j3array[1], cj3array[1], sj3array[1];
8801 bool j3valid[1]={false};
8802 _nj3 = 1;
8803 IkReal x2002=((cj6)*(sj7));
8804 IkReal x2003=((IkReal(1.00000000000000))*(sj8));
8805 IkReal x2004=((cj8)*(sj6));
8806 IkReal x2005=((sj6)*(sj8));
8807 IkReal x2006=((IkReal(1.00000000000000))*(cj6)*(cj7));
8808 if( IKabs(((gconst1)*(((((r11)*(x2004)))+(((r10)*(x2005)))+(((IkReal(-1.00000000000000))*(r12)*(x2006)))+(((cj8)*(r10)*(x2002)))+(((IkReal(-1.00000000000000))*(r11)*(x2002)*(x2003))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((r01)*(x2004)))+(((r00)*(x2005)))+(((IkReal(-1.00000000000000))*(r02)*(x2006)))+(((cj8)*(r00)*(x2002)))+(((IkReal(-1.00000000000000))*(r01)*(x2002)*(x2003))))))) < IKFAST_ATAN2_MAGTHRESH )
8809  continue;
8810 j3array[0]=IKatan2(((gconst1)*(((((r11)*(x2004)))+(((r10)*(x2005)))+(((IkReal(-1.00000000000000))*(r12)*(x2006)))+(((cj8)*(r10)*(x2002)))+(((IkReal(-1.00000000000000))*(r11)*(x2002)*(x2003)))))), ((gconst1)*(((((r01)*(x2004)))+(((r00)*(x2005)))+(((IkReal(-1.00000000000000))*(r02)*(x2006)))+(((cj8)*(r00)*(x2002)))+(((IkReal(-1.00000000000000))*(r01)*(x2002)*(x2003)))))));
8811 sj3array[0]=IKsin(j3array[0]);
8812 cj3array[0]=IKcos(j3array[0]);
8813 if( j3array[0] > IKPI )
8814 {
8815  j3array[0]-=IK2PI;
8816 }
8817 else if( j3array[0] < -IKPI )
8818 { j3array[0]+=IK2PI;
8819 }
8820 j3valid[0] = true;
8821 for(int ij3 = 0; ij3 < 1; ++ij3)
8822 {
8823 if( !j3valid[ij3] )
8824 {
8825  continue;
8826 }
8827 _ij3[0] = ij3; _ij3[1] = -1;
8828 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
8829 {
8830 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
8831 {
8832  j3valid[iij3]=false; _ij3[1] = iij3; break;
8833 }
8834 }
8835 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
8836 {
8837 IkReal evalcond[3];
8838 IkReal x2007=IKsin(j3);
8839 IkReal x2008=IKcos(j3);
8840 IkReal x2009=((IkReal(1.00000000000000))*(r11));
8841 IkReal x2010=((r01)*(sj8));
8842 IkReal x2011=((cj8)*(r10));
8843 IkReal x2012=((IkReal(1.00000000000000))*(sj7));
8844 IkReal x2013=((sj7)*(x2008));
8845 IkReal x2014=((cj7)*(x2007));
8846 IkReal x2015=((r00)*(x2007));
8847 IkReal x2016=((cj7)*(x2008));
8848 evalcond[0]=((cj6)+(((IkReal(-1.00000000000000))*(cj8)*(x2008)*(x2009)))+(((sj8)*(x2015)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2008)))+(((cj8)*(r01)*(x2007))));
8849 evalcond[1]=((((IkReal(-1.00000000000000))*(r02)*(x2007)*(x2012)))+(((IkReal(-1.00000000000000))*(sj8)*(x2009)*(x2016)))+(((x2011)*(x2016)))+(((x2010)*(x2014)))+(((r12)*(x2013)))+(((IkReal(-1.00000000000000))*(cj8)*(r00)*(x2014))));
8850 evalcond[2]=((sj6)+(((IkReal(-1.00000000000000))*(sj8)*(x2009)*(x2013)))+(((x2011)*(x2013)))+(((IkReal(-1.00000000000000))*(cj8)*(x2012)*(x2015)))+(((IkReal(-1.00000000000000))*(r12)*(x2016)))+(((sj7)*(x2007)*(x2010)))+(((r02)*(x2014))));
8851 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
8852 {
8853 continue;
8854 }
8855 }
8856 
8857 {
8858 IkReal dummyeval[1];
8859 dummyeval[0]=sj6;
8860 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8861 {
8862 {
8863 IkReal dummyeval[1];
8864 dummyeval[0]=cj6;
8865 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8866 {
8867 {
8868 IkReal evalcond[7];
8869 IkReal x2017=((IkReal(1.00000000000000))*(cj3));
8870 IkReal x2018=((cj7)*(r02));
8871 IkReal x2019=((cj8)*(sj7));
8872 IkReal x2020=((r01)*(sj3));
8873 IkReal x2021=((IkReal(1.00000000000000))*(sj3));
8874 IkReal x2022=((sj7)*(sj8));
8875 IkReal x2023=((cj7)*(r12));
8876 IkReal x2024=((cj7)*(cj8));
8877 IkReal x2025=((cj3)*(r10));
8878 IkReal x2026=((cj7)*(sj8));
8879 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
8880 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2017)))+(((r00)*(sj3)*(sj8)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2017)))+(((cj8)*(x2020))));
8881 evalcond[2]=((((IkReal(-1.00000000000000))*(r20)*(x2019)))+(((cj7)*(r22)))+(((r21)*(x2022))));
8882 evalcond[3]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x2022)))+(((IkReal(-1.00000000000000))*(npx)*(x2019)))+(((cj7)*(npz))));
8883 evalcond[4]=((((x2020)*(x2026)))+(((x2024)*(x2025)))+(((IkReal(-1.00000000000000))*(r11)*(x2017)*(x2026)))+(((cj3)*(r12)*(sj7)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x2021)))+(((IkReal(-1.00000000000000))*(r00)*(x2021)*(x2024))));
8884 evalcond[5]=((IkReal(1.00000000000000))+(((x2020)*(x2022)))+(((IkReal(-1.00000000000000))*(r11)*(x2017)*(x2022)))+(((x2019)*(x2025)))+(((IkReal(-1.00000000000000))*(r00)*(x2019)*(x2021)))+(((IkReal(-1.00000000000000))*(x2017)*(x2023)))+(((sj3)*(x2018))));
8885 evalcond[6]=((((r10)*(sj3)*(x2019)))+(((IkReal(-1.00000000000000))*(x2021)*(x2023)))+(((cj3)*(r00)*(x2019)))+(((IkReal(-1.00000000000000))*(r11)*(x2021)*(x2022)))+(((IkReal(-1.00000000000000))*(r01)*(x2017)*(x2022)))+(((IkReal(-1.00000000000000))*(x2017)*(x2018))));
8886 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
8887 {
8888 {
8889 IkReal j5array[1], cj5array[1], sj5array[1];
8890 bool j5valid[1]={false};
8891 _nj5 = 1;
8892 IkReal x2027=((IkReal(4.00000000000000))*(npx));
8893 IkReal x2028=((IkReal(4.00000000000000))*(npy));
8894 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(cj8)*(x2028)))+(((IkReal(-1.00000000000000))*(sj8)*(x2027))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((cj7)*(cj8)*(x2027)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2028)))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(cj8)*(x2028)))+(((IkReal(-1.00000000000000))*(sj8)*(x2027)))))+IKsqr(((IkReal(-0.940000000000000))+(((cj7)*(cj8)*(x2027)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2028)))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
8895  continue;
8896 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(cj8)*(x2028)))+(((IkReal(-1.00000000000000))*(sj8)*(x2027)))), ((IkReal(-0.940000000000000))+(((cj7)*(cj8)*(x2027)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2028)))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-0.360000000000000))*(cj7)))));
8897 sj5array[0]=IKsin(j5array[0]);
8898 cj5array[0]=IKcos(j5array[0]);
8899 if( j5array[0] > IKPI )
8900 {
8901  j5array[0]-=IK2PI;
8902 }
8903 else if( j5array[0] < -IKPI )
8904 { j5array[0]+=IK2PI;
8905 }
8906 j5valid[0] = true;
8907 for(int ij5 = 0; ij5 < 1; ++ij5)
8908 {
8909 if( !j5valid[ij5] )
8910 {
8911  continue;
8912 }
8913 _ij5[0] = ij5; _ij5[1] = -1;
8914 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8915 {
8916 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8917 {
8918  j5valid[iij5]=false; _ij5[1] = iij5; break;
8919 }
8920 }
8921 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8922 {
8923 IkReal evalcond[2];
8924 evalcond[0]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(IKsin(j5)))));
8925 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(cj8)*(npx)))+(((cj7)*(npy)*(sj8)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
8926 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
8927 {
8928 continue;
8929 }
8930 }
8931 
8932 {
8933 IkReal dummyeval[1];
8934 IkReal gconst56;
8935 gconst56=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
8936 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
8937 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8938 {
8939 {
8940 IkReal dummyeval[1];
8941 IkReal gconst57;
8942 gconst57=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
8943 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
8944 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
8945 {
8946 continue;
8947 
8948 } else
8949 {
8950 {
8951 IkReal j4array[1], cj4array[1], sj4array[1];
8952 bool j4valid[1]={false};
8953 _nj4 = 1;
8954 IkReal x2029=((cj8)*(sj5));
8955 IkReal x2030=((cj3)*(r01));
8956 IkReal x2031=((IkReal(1.00000000000000))*(cj5));
8957 IkReal x2032=((r11)*(sj3));
8958 IkReal x2033=((sj5)*(sj8));
8959 IkReal x2034=((r10)*(sj3));
8960 IkReal x2035=((cj3)*(r00)*(sj8));
8961 if( IKabs(((gconst57)*(((((x2033)*(x2034)))+(((cj5)*(r20)*(sj8)))+(((cj3)*(r00)*(x2033)))+(((x2029)*(x2032)))+(((x2029)*(x2030)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst57)*(((((r20)*(x2033)))+(((IkReal(-1.00000000000000))*(cj8)*(x2030)*(x2031)))+(((IkReal(-1.00000000000000))*(sj8)*(x2031)*(x2034)))+(((IkReal(-1.00000000000000))*(x2031)*(x2035)))+(((IkReal(-1.00000000000000))*(cj8)*(x2031)*(x2032)))+(((r21)*(x2029))))))) < IKFAST_ATAN2_MAGTHRESH )
8962  continue;
8963 j4array[0]=IKatan2(((gconst57)*(((((x2033)*(x2034)))+(((cj5)*(r20)*(sj8)))+(((cj3)*(r00)*(x2033)))+(((x2029)*(x2032)))+(((x2029)*(x2030)))+(((cj5)*(cj8)*(r21)))))), ((gconst57)*(((((r20)*(x2033)))+(((IkReal(-1.00000000000000))*(cj8)*(x2030)*(x2031)))+(((IkReal(-1.00000000000000))*(sj8)*(x2031)*(x2034)))+(((IkReal(-1.00000000000000))*(x2031)*(x2035)))+(((IkReal(-1.00000000000000))*(cj8)*(x2031)*(x2032)))+(((r21)*(x2029)))))));
8964 sj4array[0]=IKsin(j4array[0]);
8965 cj4array[0]=IKcos(j4array[0]);
8966 if( j4array[0] > IKPI )
8967 {
8968  j4array[0]-=IK2PI;
8969 }
8970 else if( j4array[0] < -IKPI )
8971 { j4array[0]+=IK2PI;
8972 }
8973 j4valid[0] = true;
8974 for(int ij4 = 0; ij4 < 1; ++ij4)
8975 {
8976 if( !j4valid[ij4] )
8977 {
8978  continue;
8979 }
8980 _ij4[0] = ij4; _ij4[1] = -1;
8981 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
8982 {
8983 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
8984 {
8985  j4valid[iij4]=false; _ij4[1] = iij4; break;
8986 }
8987 }
8988 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
8989 {
8990 IkReal evalcond[4];
8991 IkReal x2036=IKsin(j4);
8992 IkReal x2037=IKcos(j4);
8993 IkReal x2038=((IkReal(1.00000000000000))*(cj8));
8994 IkReal x2039=((cj3)*(r01));
8995 IkReal x2040=((cj3)*(r00));
8996 IkReal x2041=((cj7)*(cj8));
8997 IkReal x2042=((IkReal(1.00000000000000))*(cj5));
8998 IkReal x2043=((IkReal(1.00000000000000))*(sj8));
8999 IkReal x2044=((r11)*(sj3));
9000 IkReal x2045=((r10)*(sj3));
9001 IkReal x2046=((sj5)*(x2036));
9002 IkReal x2047=((sj5)*(x2037));
9003 IkReal x2048=((x2037)*(x2042));
9004 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2047)))+(((IkReal(-1.00000000000000))*(x2036)*(x2042)))+(((r20)*(sj8))));
9005 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2038)))+(((IkReal(-1.00000000000000))*(x2048)))+(x2046)+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
9006 evalcond[2]=((((IkReal(-1.00000000000000))*(x2048)))+(x2046)+(((IkReal(-1.00000000000000))*(x2040)*(x2043)))+(((IkReal(-1.00000000000000))*(x2043)*(x2045)))+(((IkReal(-1.00000000000000))*(x2038)*(x2039)))+(((IkReal(-1.00000000000000))*(x2038)*(x2044))));
9007 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x2041)*(x2045)))+(((x2040)*(x2041)))+(x2047)+(((cj3)*(r02)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2043)*(x2044)))+(((IkReal(-1.00000000000000))*(cj7)*(x2039)*(x2043)))+(((cj5)*(x2036))));
9008 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
9009 {
9010 continue;
9011 }
9012 }
9013 
9014 {
9015 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9016 vinfos[0].jointtype = 1;
9017 vinfos[0].foffset = j3;
9018 vinfos[0].indices[0] = _ij3[0];
9019 vinfos[0].indices[1] = _ij3[1];
9020 vinfos[0].maxsolutions = _nj3;
9021 vinfos[1].jointtype = 1;
9022 vinfos[1].foffset = j4;
9023 vinfos[1].indices[0] = _ij4[0];
9024 vinfos[1].indices[1] = _ij4[1];
9025 vinfos[1].maxsolutions = _nj4;
9026 vinfos[2].jointtype = 1;
9027 vinfos[2].foffset = j5;
9028 vinfos[2].indices[0] = _ij5[0];
9029 vinfos[2].indices[1] = _ij5[1];
9030 vinfos[2].maxsolutions = _nj5;
9031 vinfos[3].jointtype = 1;
9032 vinfos[3].foffset = j6;
9033 vinfos[3].indices[0] = _ij6[0];
9034 vinfos[3].indices[1] = _ij6[1];
9035 vinfos[3].maxsolutions = _nj6;
9036 vinfos[4].jointtype = 1;
9037 vinfos[4].foffset = j7;
9038 vinfos[4].indices[0] = _ij7[0];
9039 vinfos[4].indices[1] = _ij7[1];
9040 vinfos[4].maxsolutions = _nj7;
9041 vinfos[5].jointtype = 1;
9042 vinfos[5].foffset = j8;
9043 vinfos[5].indices[0] = _ij8[0];
9044 vinfos[5].indices[1] = _ij8[1];
9045 vinfos[5].maxsolutions = _nj8;
9046 std::vector<int> vfree(0);
9047 solutions.AddSolution(vinfos,vfree);
9048 }
9049 }
9050 }
9051 
9052 }
9053 
9054 }
9055 
9056 } else
9057 {
9058 {
9059 IkReal j4array[1], cj4array[1], sj4array[1];
9060 bool j4valid[1]={false};
9061 _nj4 = 1;
9062 IkReal x2049=((cj7)*(sj5));
9063 IkReal x2050=((r21)*(sj8));
9064 IkReal x2051=((cj8)*(r20));
9065 IkReal x2052=((cj5)*(cj7));
9066 IkReal x2053=((r22)*(sj7));
9067 IkReal x2054=((cj8)*(r21));
9068 IkReal x2055=((r20)*(sj8));
9069 if( IKabs(((gconst56)*(((((cj5)*(x2054)))+(((cj5)*(x2055)))+(((x2049)*(x2051)))+(((sj5)*(x2053)))+(((IkReal(-1.00000000000000))*(x2049)*(x2050))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst56)*(((((sj5)*(x2054)))+(((sj5)*(x2055)))+(((IkReal(-1.00000000000000))*(x2051)*(x2052)))+(((x2050)*(x2052)))+(((IkReal(-1.00000000000000))*(cj5)*(x2053))))))) < IKFAST_ATAN2_MAGTHRESH )
9070  continue;
9071 j4array[0]=IKatan2(((gconst56)*(((((cj5)*(x2054)))+(((cj5)*(x2055)))+(((x2049)*(x2051)))+(((sj5)*(x2053)))+(((IkReal(-1.00000000000000))*(x2049)*(x2050)))))), ((gconst56)*(((((sj5)*(x2054)))+(((sj5)*(x2055)))+(((IkReal(-1.00000000000000))*(x2051)*(x2052)))+(((x2050)*(x2052)))+(((IkReal(-1.00000000000000))*(cj5)*(x2053)))))));
9072 sj4array[0]=IKsin(j4array[0]);
9073 cj4array[0]=IKcos(j4array[0]);
9074 if( j4array[0] > IKPI )
9075 {
9076  j4array[0]-=IK2PI;
9077 }
9078 else if( j4array[0] < -IKPI )
9079 { j4array[0]+=IK2PI;
9080 }
9081 j4valid[0] = true;
9082 for(int ij4 = 0; ij4 < 1; ++ij4)
9083 {
9084 if( !j4valid[ij4] )
9085 {
9086  continue;
9087 }
9088 _ij4[0] = ij4; _ij4[1] = -1;
9089 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
9090 {
9091 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
9092 {
9093  j4valid[iij4]=false; _ij4[1] = iij4; break;
9094 }
9095 }
9096 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
9097 {
9098 IkReal evalcond[4];
9099 IkReal x2056=IKsin(j4);
9100 IkReal x2057=IKcos(j4);
9101 IkReal x2058=((IkReal(1.00000000000000))*(cj8));
9102 IkReal x2059=((cj3)*(r01));
9103 IkReal x2060=((cj3)*(r00));
9104 IkReal x2061=((cj7)*(cj8));
9105 IkReal x2062=((IkReal(1.00000000000000))*(cj5));
9106 IkReal x2063=((IkReal(1.00000000000000))*(sj8));
9107 IkReal x2064=((r11)*(sj3));
9108 IkReal x2065=((r10)*(sj3));
9109 IkReal x2066=((sj5)*(x2056));
9110 IkReal x2067=((sj5)*(x2057));
9111 IkReal x2068=((x2057)*(x2062));
9112 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2067)))+(((IkReal(-1.00000000000000))*(x2056)*(x2062)))+(((r20)*(sj8))));
9113 evalcond[1]=((x2066)+(((IkReal(-1.00000000000000))*(x2068)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2058))));
9114 evalcond[2]=((((IkReal(-1.00000000000000))*(x2058)*(x2059)))+(((IkReal(-1.00000000000000))*(x2063)*(x2065)))+(((IkReal(-1.00000000000000))*(x2058)*(x2064)))+(x2066)+(((IkReal(-1.00000000000000))*(x2068)))+(((IkReal(-1.00000000000000))*(x2060)*(x2063))));
9115 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((cj5)*(x2056)))+(x2067)+(((IkReal(-1.00000000000000))*(cj7)*(x2059)*(x2063)))+(((x2060)*(x2061)))+(((cj3)*(r02)*(sj7)))+(((x2061)*(x2065)))+(((IkReal(-1.00000000000000))*(cj7)*(x2063)*(x2064))));
9116 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
9117 {
9118 continue;
9119 }
9120 }
9121 
9122 {
9123 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9124 vinfos[0].jointtype = 1;
9125 vinfos[0].foffset = j3;
9126 vinfos[0].indices[0] = _ij3[0];
9127 vinfos[0].indices[1] = _ij3[1];
9128 vinfos[0].maxsolutions = _nj3;
9129 vinfos[1].jointtype = 1;
9130 vinfos[1].foffset = j4;
9131 vinfos[1].indices[0] = _ij4[0];
9132 vinfos[1].indices[1] = _ij4[1];
9133 vinfos[1].maxsolutions = _nj4;
9134 vinfos[2].jointtype = 1;
9135 vinfos[2].foffset = j5;
9136 vinfos[2].indices[0] = _ij5[0];
9137 vinfos[2].indices[1] = _ij5[1];
9138 vinfos[2].maxsolutions = _nj5;
9139 vinfos[3].jointtype = 1;
9140 vinfos[3].foffset = j6;
9141 vinfos[3].indices[0] = _ij6[0];
9142 vinfos[3].indices[1] = _ij6[1];
9143 vinfos[3].maxsolutions = _nj6;
9144 vinfos[4].jointtype = 1;
9145 vinfos[4].foffset = j7;
9146 vinfos[4].indices[0] = _ij7[0];
9147 vinfos[4].indices[1] = _ij7[1];
9148 vinfos[4].maxsolutions = _nj7;
9149 vinfos[5].jointtype = 1;
9150 vinfos[5].foffset = j8;
9151 vinfos[5].indices[0] = _ij8[0];
9152 vinfos[5].indices[1] = _ij8[1];
9153 vinfos[5].maxsolutions = _nj8;
9154 std::vector<int> vfree(0);
9155 solutions.AddSolution(vinfos,vfree);
9156 }
9157 }
9158 }
9159 
9160 }
9161 
9162 }
9163 }
9164 }
9165 
9166 } else
9167 {
9168 IkReal x2069=((IkReal(1.00000000000000))*(cj3));
9169 IkReal x2070=((cj7)*(r02));
9170 IkReal x2071=((cj8)*(sj7));
9171 IkReal x2072=((r01)*(sj3));
9172 IkReal x2073=((IkReal(1.00000000000000))*(sj3));
9173 IkReal x2074=((sj7)*(sj8));
9174 IkReal x2075=((cj7)*(r12));
9175 IkReal x2076=((cj7)*(cj8));
9176 IkReal x2077=((cj3)*(r10));
9177 IkReal x2078=((cj7)*(sj8));
9178 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
9179 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2069)))+(((r00)*(sj3)*(sj8)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2069)))+(((cj8)*(x2072))));
9180 evalcond[2]=((((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x2071)))+(((r21)*(x2074))));
9181 evalcond[3]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x2074)))+(((cj7)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(x2071))));
9182 evalcond[4]=((((IkReal(-1.00000000000000))*(r11)*(x2069)*(x2078)))+(((cj3)*(r12)*(sj7)))+(((IkReal(-1.00000000000000))*(r00)*(x2073)*(x2076)))+(((x2076)*(x2077)))+(((x2072)*(x2078)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x2073))));
9183 evalcond[5]=((IkReal(-1.00000000000000))+(((sj3)*(x2070)))+(((IkReal(-1.00000000000000))*(r00)*(x2071)*(x2073)))+(((IkReal(-1.00000000000000))*(r11)*(x2069)*(x2074)))+(((x2071)*(x2077)))+(((IkReal(-1.00000000000000))*(x2069)*(x2075)))+(((x2072)*(x2074))));
9184 evalcond[6]=((((cj3)*(r00)*(x2071)))+(((IkReal(-1.00000000000000))*(x2069)*(x2070)))+(((IkReal(-1.00000000000000))*(x2073)*(x2075)))+(((IkReal(-1.00000000000000))*(r01)*(x2069)*(x2074)))+(((IkReal(-1.00000000000000))*(r11)*(x2073)*(x2074)))+(((r10)*(sj3)*(x2071))));
9185 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
9186 {
9187 {
9188 IkReal j5array[1], cj5array[1], sj5array[1];
9189 bool j5valid[1]={false};
9190 _nj5 = 1;
9191 IkReal x2079=((IkReal(4.00000000000000))*(npx));
9192 IkReal x2080=((IkReal(4.00000000000000))*(npy));
9193 if( IKabs(((IkReal(0.120000000000000))+(((cj8)*(x2080)))+(((sj8)*(x2079))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2080)))+(((cj7)*(cj8)*(x2079)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((cj8)*(x2080)))+(((sj8)*(x2079)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2080)))+(((cj7)*(cj8)*(x2079)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
9194  continue;
9195 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((cj8)*(x2080)))+(((sj8)*(x2079)))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2080)))+(((cj7)*(cj8)*(x2079)))+(((IkReal(-0.360000000000000))*(cj7)))));
9196 sj5array[0]=IKsin(j5array[0]);
9197 cj5array[0]=IKcos(j5array[0]);
9198 if( j5array[0] > IKPI )
9199 {
9200  j5array[0]-=IK2PI;
9201 }
9202 else if( j5array[0] < -IKPI )
9203 { j5array[0]+=IK2PI;
9204 }
9205 j5valid[0] = true;
9206 for(int ij5 = 0; ij5 < 1; ++ij5)
9207 {
9208 if( !j5valid[ij5] )
9209 {
9210  continue;
9211 }
9212 _ij5[0] = ij5; _ij5[1] = -1;
9213 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9214 {
9215 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9216 {
9217  j5valid[iij5]=false; _ij5[1] = iij5; break;
9218 }
9219 }
9220 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9221 {
9222 IkReal evalcond[2];
9223 evalcond[0]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(IKsin(j5)))));
9224 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(cj8)*(npx)))+(((cj7)*(npy)*(sj8)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
9225 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
9226 {
9227 continue;
9228 }
9229 }
9230 
9231 {
9232 IkReal dummyeval[1];
9233 IkReal gconst58;
9234 gconst58=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
9235 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
9236 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
9237 {
9238 {
9239 IkReal dummyeval[1];
9240 IkReal gconst59;
9241 gconst59=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
9242 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
9243 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
9244 {
9245 continue;
9246 
9247 } else
9248 {
9249 {
9250 IkReal j4array[1], cj4array[1], sj4array[1];
9251 bool j4valid[1]={false};
9252 _nj4 = 1;
9253 IkReal x2081=((IkReal(1.00000000000000))*(sj5));
9254 IkReal x2082=((r20)*(sj8));
9255 IkReal x2083=((cj5)*(cj8));
9256 IkReal x2084=((r11)*(sj3));
9257 IkReal x2085=((cj3)*(r01));
9258 IkReal x2086=((cj3)*(r00)*(sj8));
9259 IkReal x2087=((r10)*(sj3)*(sj8));
9260 if( IKabs(((gconst59)*(((((IkReal(-1.00000000000000))*(r21)*(x2083)))+(((IkReal(-1.00000000000000))*(x2081)*(x2086)))+(((IkReal(-1.00000000000000))*(x2081)*(x2087)))+(((IkReal(-1.00000000000000))*(cj8)*(x2081)*(x2085)))+(((IkReal(-1.00000000000000))*(cj8)*(x2081)*(x2084)))+(((IkReal(-1.00000000000000))*(cj5)*(x2082))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst59)*(((((IkReal(-1.00000000000000))*(x2081)*(x2082)))+(((cj5)*(x2087)))+(((cj5)*(x2086)))+(((x2083)*(x2084)))+(((x2083)*(x2085)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2081))))))) < IKFAST_ATAN2_MAGTHRESH )
9261  continue;
9262 j4array[0]=IKatan2(((gconst59)*(((((IkReal(-1.00000000000000))*(r21)*(x2083)))+(((IkReal(-1.00000000000000))*(x2081)*(x2086)))+(((IkReal(-1.00000000000000))*(x2081)*(x2087)))+(((IkReal(-1.00000000000000))*(cj8)*(x2081)*(x2085)))+(((IkReal(-1.00000000000000))*(cj8)*(x2081)*(x2084)))+(((IkReal(-1.00000000000000))*(cj5)*(x2082)))))), ((gconst59)*(((((IkReal(-1.00000000000000))*(x2081)*(x2082)))+(((cj5)*(x2087)))+(((cj5)*(x2086)))+(((x2083)*(x2084)))+(((x2083)*(x2085)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2081)))))));
9263 sj4array[0]=IKsin(j4array[0]);
9264 cj4array[0]=IKcos(j4array[0]);
9265 if( j4array[0] > IKPI )
9266 {
9267  j4array[0]-=IK2PI;
9268 }
9269 else if( j4array[0] < -IKPI )
9270 { j4array[0]+=IK2PI;
9271 }
9272 j4valid[0] = true;
9273 for(int ij4 = 0; ij4 < 1; ++ij4)
9274 {
9275 if( !j4valid[ij4] )
9276 {
9277  continue;
9278 }
9279 _ij4[0] = ij4; _ij4[1] = -1;
9280 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
9281 {
9282 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
9283 {
9284  j4valid[iij4]=false; _ij4[1] = iij4; break;
9285 }
9286 }
9287 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
9288 {
9289 IkReal evalcond[4];
9290 IkReal x2088=IKsin(j4);
9291 IkReal x2089=IKcos(j4);
9292 IkReal x2090=((IkReal(1.00000000000000))*(cj8));
9293 IkReal x2091=((cj3)*(r01));
9294 IkReal x2092=((cj3)*(r00));
9295 IkReal x2093=((cj7)*(cj8));
9296 IkReal x2094=((r11)*(sj3));
9297 IkReal x2095=((IkReal(1.00000000000000))*(sj8));
9298 IkReal x2096=((r10)*(sj3));
9299 IkReal x2097=((sj5)*(x2089));
9300 IkReal x2098=((cj5)*(x2088));
9301 IkReal x2099=((cj5)*(x2089));
9302 IkReal x2100=((sj5)*(x2088));
9303 IkReal x2101=((x2097)+(x2098));
9304 evalcond[0]=((x2101)+(((cj8)*(r21)))+(((r20)*(sj8))));
9305 evalcond[1]=((x2100)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2090)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x2099)))+(((cj7)*(r21)*(sj8))));
9306 evalcond[2]=((((IkReal(-1.00000000000000))*(x2090)*(x2094)))+(((IkReal(-1.00000000000000))*(x2090)*(x2091)))+(x2099)+(((IkReal(-1.00000000000000))*(x2095)*(x2096)))+(((IkReal(-1.00000000000000))*(x2092)*(x2095)))+(((IkReal(-1.00000000000000))*(x2100))));
9307 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2094)*(x2095)))+(((IkReal(-1.00000000000000))*(cj7)*(x2091)*(x2095)))+(x2101)+(((x2092)*(x2093)))+(((cj3)*(r02)*(sj7)))+(((x2093)*(x2096))));
9308 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
9309 {
9310 continue;
9311 }
9312 }
9313 
9314 {
9315 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9316 vinfos[0].jointtype = 1;
9317 vinfos[0].foffset = j3;
9318 vinfos[0].indices[0] = _ij3[0];
9319 vinfos[0].indices[1] = _ij3[1];
9320 vinfos[0].maxsolutions = _nj3;
9321 vinfos[1].jointtype = 1;
9322 vinfos[1].foffset = j4;
9323 vinfos[1].indices[0] = _ij4[0];
9324 vinfos[1].indices[1] = _ij4[1];
9325 vinfos[1].maxsolutions = _nj4;
9326 vinfos[2].jointtype = 1;
9327 vinfos[2].foffset = j5;
9328 vinfos[2].indices[0] = _ij5[0];
9329 vinfos[2].indices[1] = _ij5[1];
9330 vinfos[2].maxsolutions = _nj5;
9331 vinfos[3].jointtype = 1;
9332 vinfos[3].foffset = j6;
9333 vinfos[3].indices[0] = _ij6[0];
9334 vinfos[3].indices[1] = _ij6[1];
9335 vinfos[3].maxsolutions = _nj6;
9336 vinfos[4].jointtype = 1;
9337 vinfos[4].foffset = j7;
9338 vinfos[4].indices[0] = _ij7[0];
9339 vinfos[4].indices[1] = _ij7[1];
9340 vinfos[4].maxsolutions = _nj7;
9341 vinfos[5].jointtype = 1;
9342 vinfos[5].foffset = j8;
9343 vinfos[5].indices[0] = _ij8[0];
9344 vinfos[5].indices[1] = _ij8[1];
9345 vinfos[5].maxsolutions = _nj8;
9346 std::vector<int> vfree(0);
9347 solutions.AddSolution(vinfos,vfree);
9348 }
9349 }
9350 }
9351 
9352 }
9353 
9354 }
9355 
9356 } else
9357 {
9358 {
9359 IkReal j4array[1], cj4array[1], sj4array[1];
9360 bool j4valid[1]={false};
9361 _nj4 = 1;
9362 IkReal x2102=((r22)*(sj7));
9363 IkReal x2103=((cj8)*(sj5));
9364 IkReal x2104=((sj5)*(sj8));
9365 IkReal x2105=((cj7)*(r20));
9366 IkReal x2106=((cj5)*(cj8));
9367 IkReal x2107=((cj7)*(r21));
9368 IkReal x2108=((cj5)*(sj8));
9369 if( IKabs(((gconst58)*(((((r20)*(x2108)))+(((IkReal(-1.00000000000000))*(x2103)*(x2105)))+(((r21)*(x2106)))+(((x2104)*(x2107)))+(((IkReal(-1.00000000000000))*(sj5)*(x2102))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst58)*(((((r20)*(x2104)))+(((cj5)*(x2102)))+(((r21)*(x2103)))+(((IkReal(-1.00000000000000))*(x2107)*(x2108)))+(((x2105)*(x2106))))))) < IKFAST_ATAN2_MAGTHRESH )
9370  continue;
9371 j4array[0]=IKatan2(((gconst58)*(((((r20)*(x2108)))+(((IkReal(-1.00000000000000))*(x2103)*(x2105)))+(((r21)*(x2106)))+(((x2104)*(x2107)))+(((IkReal(-1.00000000000000))*(sj5)*(x2102)))))), ((gconst58)*(((((r20)*(x2104)))+(((cj5)*(x2102)))+(((r21)*(x2103)))+(((IkReal(-1.00000000000000))*(x2107)*(x2108)))+(((x2105)*(x2106)))))));
9372 sj4array[0]=IKsin(j4array[0]);
9373 cj4array[0]=IKcos(j4array[0]);
9374 if( j4array[0] > IKPI )
9375 {
9376  j4array[0]-=IK2PI;
9377 }
9378 else if( j4array[0] < -IKPI )
9379 { j4array[0]+=IK2PI;
9380 }
9381 j4valid[0] = true;
9382 for(int ij4 = 0; ij4 < 1; ++ij4)
9383 {
9384 if( !j4valid[ij4] )
9385 {
9386  continue;
9387 }
9388 _ij4[0] = ij4; _ij4[1] = -1;
9389 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
9390 {
9391 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
9392 {
9393  j4valid[iij4]=false; _ij4[1] = iij4; break;
9394 }
9395 }
9396 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
9397 {
9398 IkReal evalcond[4];
9399 IkReal x2109=IKsin(j4);
9400 IkReal x2110=IKcos(j4);
9401 IkReal x2111=((IkReal(1.00000000000000))*(cj8));
9402 IkReal x2112=((cj3)*(r01));
9403 IkReal x2113=((cj3)*(r00));
9404 IkReal x2114=((cj7)*(cj8));
9405 IkReal x2115=((r11)*(sj3));
9406 IkReal x2116=((IkReal(1.00000000000000))*(sj8));
9407 IkReal x2117=((r10)*(sj3));
9408 IkReal x2118=((sj5)*(x2110));
9409 IkReal x2119=((cj5)*(x2109));
9410 IkReal x2120=((cj5)*(x2110));
9411 IkReal x2121=((sj5)*(x2109));
9412 IkReal x2122=((x2118)+(x2119));
9413 evalcond[0]=((x2122)+(((cj8)*(r21)))+(((r20)*(sj8))));
9414 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2111)))+(x2121)+(((IkReal(-1.00000000000000))*(x2120)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
9415 evalcond[2]=((((IkReal(-1.00000000000000))*(x2116)*(x2117)))+(x2120)+(((IkReal(-1.00000000000000))*(x2121)))+(((IkReal(-1.00000000000000))*(x2111)*(x2112)))+(((IkReal(-1.00000000000000))*(x2111)*(x2115)))+(((IkReal(-1.00000000000000))*(x2113)*(x2116))));
9416 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2115)*(x2116)))+(((IkReal(-1.00000000000000))*(cj7)*(x2112)*(x2116)))+(x2122)+(((cj3)*(r02)*(sj7)))+(((x2113)*(x2114)))+(((x2114)*(x2117))));
9417 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
9418 {
9419 continue;
9420 }
9421 }
9422 
9423 {
9424 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9425 vinfos[0].jointtype = 1;
9426 vinfos[0].foffset = j3;
9427 vinfos[0].indices[0] = _ij3[0];
9428 vinfos[0].indices[1] = _ij3[1];
9429 vinfos[0].maxsolutions = _nj3;
9430 vinfos[1].jointtype = 1;
9431 vinfos[1].foffset = j4;
9432 vinfos[1].indices[0] = _ij4[0];
9433 vinfos[1].indices[1] = _ij4[1];
9434 vinfos[1].maxsolutions = _nj4;
9435 vinfos[2].jointtype = 1;
9436 vinfos[2].foffset = j5;
9437 vinfos[2].indices[0] = _ij5[0];
9438 vinfos[2].indices[1] = _ij5[1];
9439 vinfos[2].maxsolutions = _nj5;
9440 vinfos[3].jointtype = 1;
9441 vinfos[3].foffset = j6;
9442 vinfos[3].indices[0] = _ij6[0];
9443 vinfos[3].indices[1] = _ij6[1];
9444 vinfos[3].maxsolutions = _nj6;
9445 vinfos[4].jointtype = 1;
9446 vinfos[4].foffset = j7;
9447 vinfos[4].indices[0] = _ij7[0];
9448 vinfos[4].indices[1] = _ij7[1];
9449 vinfos[4].maxsolutions = _nj7;
9450 vinfos[5].jointtype = 1;
9451 vinfos[5].foffset = j8;
9452 vinfos[5].indices[0] = _ij8[0];
9453 vinfos[5].indices[1] = _ij8[1];
9454 vinfos[5].maxsolutions = _nj8;
9455 std::vector<int> vfree(0);
9456 solutions.AddSolution(vinfos,vfree);
9457 }
9458 }
9459 }
9460 
9461 }
9462 
9463 }
9464 }
9465 }
9466 
9467 } else
9468 {
9469 IkReal x2123=((cj3)*(cj8));
9470 IkReal x2124=((r01)*(sj3));
9471 IkReal x2125=((r02)*(sj3));
9472 IkReal x2126=((IkReal(1.00000000000000))*(sj7));
9473 IkReal x2127=((IkReal(1.00000000000000))*(r11));
9474 IkReal x2128=((cj3)*(r12));
9475 IkReal x2129=((IkReal(1.00000000000000))*(cj7));
9476 IkReal x2130=((cj8)*(sj3));
9477 IkReal x2131=((sj3)*(sj8));
9478 IkReal x2132=((IkReal(1.00000000000000))*(cj3)*(sj8));
9479 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
9480 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
9481 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
9482 evalcond[3]=((IkReal(1.00000000000000))+(((r00)*(x2131)))+(((cj8)*(x2124)))+(((IkReal(-1.00000000000000))*(r10)*(x2132)))+(((IkReal(-1.00000000000000))*(x2123)*(x2127))));
9483 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x2132)))+(((IkReal(-1.00000000000000))*(x2127)*(x2130)))+(((IkReal(-1.00000000000000))*(r10)*(x2131)))+(((IkReal(-1.00000000000000))*(r01)*(x2123))));
9484 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x2129)*(x2130)))+(((cj7)*(sj8)*(x2124)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x2127)))+(((IkReal(-1.00000000000000))*(x2125)*(x2126)))+(((sj7)*(x2128)))+(((cj7)*(r10)*(x2123))));
9485 evalcond[6]=((((cj7)*(x2125)))+(((IkReal(-1.00000000000000))*(r00)*(x2126)*(x2130)))+(((sj7)*(sj8)*(x2124)))+(((IkReal(-1.00000000000000))*(x2128)*(x2129)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x2126)))+(((r10)*(sj7)*(x2123))));
9486 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
9487 {
9488 {
9489 IkReal j5array[1], cj5array[1], sj5array[1];
9490 bool j5valid[1]={false};
9491 _nj5 = 1;
9492 IkReal x2133=((IkReal(4.00000000000000))*(sj7));
9493 IkReal x2134=((npy)*(sj8));
9494 IkReal x2135=((IkReal(4.00000000000000))*(cj7));
9495 IkReal x2136=((cj8)*(npx));
9496 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj7)))+(((npz)*(x2135)))+(((IkReal(-1.00000000000000))*(x2133)*(x2136)))+(((x2133)*(x2134))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x2134)*(x2135)))+(((x2135)*(x2136)))+(((npz)*(x2133)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj7)))+(((npz)*(x2135)))+(((IkReal(-1.00000000000000))*(x2133)*(x2136)))+(((x2133)*(x2134)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x2134)*(x2135)))+(((x2135)*(x2136)))+(((npz)*(x2133)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
9497  continue;
9498 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj7)))+(((npz)*(x2135)))+(((IkReal(-1.00000000000000))*(x2133)*(x2136)))+(((x2133)*(x2134)))), ((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x2134)*(x2135)))+(((x2135)*(x2136)))+(((npz)*(x2133)))+(((IkReal(-0.360000000000000))*(cj7)))));
9499 sj5array[0]=IKsin(j5array[0]);
9500 cj5array[0]=IKcos(j5array[0]);
9501 if( j5array[0] > IKPI )
9502 {
9503  j5array[0]-=IK2PI;
9504 }
9505 else if( j5array[0] < -IKPI )
9506 { j5array[0]+=IK2PI;
9507 }
9508 j5valid[0] = true;
9509 for(int ij5 = 0; ij5 < 1; ++ij5)
9510 {
9511 if( !j5valid[ij5] )
9512 {
9513  continue;
9514 }
9515 _ij5[0] = ij5; _ij5[1] = -1;
9516 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9517 {
9518 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9519 {
9520  j5valid[iij5]=false; _ij5[1] = iij5; break;
9521 }
9522 }
9523 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9524 {
9525 IkReal evalcond[2];
9526 IkReal x2137=((IkReal(1.00000000000000))*(sj7));
9527 IkReal x2138=((npy)*(sj8));
9528 IkReal x2139=((cj8)*(npx));
9529 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(cj7)*(x2139)))+(((IkReal(0.0900000000000000))*(cj7)))+(((cj7)*(x2138)))+(((IkReal(-1.00000000000000))*(npz)*(x2137)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
9530 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x2138)))+(((IkReal(-0.250000000000000))*(IKsin(j5))))+(((IkReal(-1.00000000000000))*(x2137)*(x2139)))+(((cj7)*(npz))));
9531 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
9532 {
9533 continue;
9534 }
9535 }
9536 
9537 {
9538 IkReal dummyeval[1];
9539 IkReal gconst60;
9540 gconst60=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
9541 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
9542 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
9543 {
9544 {
9545 IkReal dummyeval[1];
9546 IkReal gconst61;
9547 gconst61=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
9548 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
9549 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
9550 {
9551 continue;
9552 
9553 } else
9554 {
9555 {
9556 IkReal j4array[1], cj4array[1], sj4array[1];
9557 bool j4valid[1]={false};
9558 _nj4 = 1;
9559 IkReal x2140=((cj3)*(cj5));
9560 IkReal x2141=((r02)*(sj7));
9561 IkReal x2142=((cj8)*(r00));
9562 IkReal x2143=((cj5)*(sj7));
9563 IkReal x2144=((cj5)*(sj3));
9564 IkReal x2145=((cj7)*(cj8));
9565 IkReal x2146=((IkReal(1.00000000000000))*(sj5));
9566 IkReal x2147=((r12)*(sj3));
9567 IkReal x2148=((sj3)*(sj5));
9568 IkReal x2149=((cj3)*(cj7)*(sj5));
9569 IkReal x2150=((IkReal(1.00000000000000))*(cj7)*(sj8));
9570 if( IKabs(((gconst61)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r11)*(x2144)*(x2150)))+(((cj7)*(x2140)*(x2142)))+(((x2143)*(x2147)))+(((IkReal(-1.00000000000000))*(r01)*(x2140)*(x2150)))+(((x2140)*(x2141)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2146)))+(((r10)*(x2144)*(x2145)))+(((IkReal(-1.00000000000000))*(r20)*(x2145)*(x2146))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst61)*(((((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x2146)))+(((sj5)*(sj7)*(x2147)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2146)))+(((r10)*(x2145)*(x2148)))+(((cj5)*(r20)*(x2145)))+(((x2142)*(x2149)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2150)))+(((r22)*(x2143)))+(((cj3)*(sj5)*(x2141))))))) < IKFAST_ATAN2_MAGTHRESH )
9571  continue;
9572 j4array[0]=IKatan2(((gconst61)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r11)*(x2144)*(x2150)))+(((cj7)*(x2140)*(x2142)))+(((x2143)*(x2147)))+(((IkReal(-1.00000000000000))*(r01)*(x2140)*(x2150)))+(((x2140)*(x2141)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2146)))+(((r10)*(x2144)*(x2145)))+(((IkReal(-1.00000000000000))*(r20)*(x2145)*(x2146)))))), ((gconst61)*(((((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x2146)))+(((sj5)*(sj7)*(x2147)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2146)))+(((r10)*(x2145)*(x2148)))+(((cj5)*(r20)*(x2145)))+(((x2142)*(x2149)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2150)))+(((r22)*(x2143)))+(((cj3)*(sj5)*(x2141)))))));
9573 sj4array[0]=IKsin(j4array[0]);
9574 cj4array[0]=IKcos(j4array[0]);
9575 if( j4array[0] > IKPI )
9576 {
9577  j4array[0]-=IK2PI;
9578 }
9579 else if( j4array[0] < -IKPI )
9580 { j4array[0]+=IK2PI;
9581 }
9582 j4valid[0] = true;
9583 for(int ij4 = 0; ij4 < 1; ++ij4)
9584 {
9585 if( !j4valid[ij4] )
9586 {
9587  continue;
9588 }
9589 _ij4[0] = ij4; _ij4[1] = -1;
9590 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
9591 {
9592 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
9593 {
9594  j4valid[iij4]=false; _ij4[1] = iij4; break;
9595 }
9596 }
9597 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
9598 {
9599 IkReal evalcond[4];
9600 IkReal x2151=IKcos(j4);
9601 IkReal x2152=IKsin(j4);
9602 IkReal x2153=((IkReal(1.00000000000000))*(cj7));
9603 IkReal x2154=((cj8)*(r20));
9604 IkReal x2155=((cj3)*(r02));
9605 IkReal x2156=((IkReal(1.00000000000000))*(sj7));
9606 IkReal x2157=((sj3)*(sj7));
9607 IkReal x2158=((r21)*(sj8));
9608 IkReal x2159=((cj8)*(r10));
9609 IkReal x2160=((sj5)*(x2151));
9610 IkReal x2161=((cj5)*(x2152));
9611 IkReal x2162=((r11)*(sj3)*(sj8));
9612 IkReal x2163=((cj3)*(cj8)*(r00));
9613 IkReal x2164=((cj5)*(x2151));
9614 IkReal x2165=((cj3)*(r01)*(sj8));
9615 IkReal x2166=((sj5)*(x2152));
9616 IkReal x2167=((x2161)+(x2160));
9617 evalcond[0]=((x2166)+(((IkReal(-1.00000000000000))*(x2153)*(x2154)))+(((cj7)*(x2158)))+(((IkReal(-1.00000000000000))*(r22)*(x2156)))+(((IkReal(-1.00000000000000))*(x2164))));
9618 evalcond[1]=((x2167)+(((sj7)*(x2158)))+(((IkReal(-1.00000000000000))*(x2154)*(x2156)))+(((cj7)*(r22))));
9619 evalcond[2]=((((IkReal(-1.00000000000000))*(x2153)*(x2162)))+(((IkReal(-1.00000000000000))*(x2153)*(x2165)))+(((cj7)*(x2163)))+(x2167)+(((sj7)*(x2155)))+(((r12)*(x2157)))+(((cj7)*(sj3)*(x2159))));
9620 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2153)))+(((sj7)*(x2163)))+(x2164)+(((IkReal(-1.00000000000000))*(x2153)*(x2155)))+(((IkReal(-1.00000000000000))*(x2156)*(x2162)))+(((IkReal(-1.00000000000000))*(x2156)*(x2165)))+(((IkReal(-1.00000000000000))*(x2166)))+(((x2157)*(x2159))));
9621 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
9622 {
9623 continue;
9624 }
9625 }
9626 
9627 {
9628 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9629 vinfos[0].jointtype = 1;
9630 vinfos[0].foffset = j3;
9631 vinfos[0].indices[0] = _ij3[0];
9632 vinfos[0].indices[1] = _ij3[1];
9633 vinfos[0].maxsolutions = _nj3;
9634 vinfos[1].jointtype = 1;
9635 vinfos[1].foffset = j4;
9636 vinfos[1].indices[0] = _ij4[0];
9637 vinfos[1].indices[1] = _ij4[1];
9638 vinfos[1].maxsolutions = _nj4;
9639 vinfos[2].jointtype = 1;
9640 vinfos[2].foffset = j5;
9641 vinfos[2].indices[0] = _ij5[0];
9642 vinfos[2].indices[1] = _ij5[1];
9643 vinfos[2].maxsolutions = _nj5;
9644 vinfos[3].jointtype = 1;
9645 vinfos[3].foffset = j6;
9646 vinfos[3].indices[0] = _ij6[0];
9647 vinfos[3].indices[1] = _ij6[1];
9648 vinfos[3].maxsolutions = _nj6;
9649 vinfos[4].jointtype = 1;
9650 vinfos[4].foffset = j7;
9651 vinfos[4].indices[0] = _ij7[0];
9652 vinfos[4].indices[1] = _ij7[1];
9653 vinfos[4].maxsolutions = _nj7;
9654 vinfos[5].jointtype = 1;
9655 vinfos[5].foffset = j8;
9656 vinfos[5].indices[0] = _ij8[0];
9657 vinfos[5].indices[1] = _ij8[1];
9658 vinfos[5].maxsolutions = _nj8;
9659 std::vector<int> vfree(0);
9660 solutions.AddSolution(vinfos,vfree);
9661 }
9662 }
9663 }
9664 
9665 }
9666 
9667 }
9668 
9669 } else
9670 {
9671 {
9672 IkReal j4array[1], cj4array[1], sj4array[1];
9673 bool j4valid[1]={false};
9674 _nj4 = 1;
9675 IkReal x2168=((sj5)*(sj7));
9676 IkReal x2169=((r21)*(sj8));
9677 IkReal x2170=((cj5)*(sj7));
9678 IkReal x2171=((cj8)*(r20));
9679 IkReal x2172=((cj5)*(cj7));
9680 IkReal x2173=((cj7)*(sj5));
9681 if( IKabs(((gconst60)*(((((r22)*(x2172)))+(((IkReal(-1.00000000000000))*(x2171)*(x2173)))+(((IkReal(-1.00000000000000))*(r22)*(x2168)))+(((IkReal(-1.00000000000000))*(x2170)*(x2171)))+(((x2169)*(x2170)))+(((x2169)*(x2173))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst60)*(((((x2168)*(x2169)))+(((r22)*(x2173)))+(((r22)*(x2170)))+(((IkReal(-1.00000000000000))*(x2168)*(x2171)))+(((IkReal(-1.00000000000000))*(x2169)*(x2172)))+(((x2171)*(x2172))))))) < IKFAST_ATAN2_MAGTHRESH )
9682  continue;
9683 j4array[0]=IKatan2(((gconst60)*(((((r22)*(x2172)))+(((IkReal(-1.00000000000000))*(x2171)*(x2173)))+(((IkReal(-1.00000000000000))*(r22)*(x2168)))+(((IkReal(-1.00000000000000))*(x2170)*(x2171)))+(((x2169)*(x2170)))+(((x2169)*(x2173)))))), ((gconst60)*(((((x2168)*(x2169)))+(((r22)*(x2173)))+(((r22)*(x2170)))+(((IkReal(-1.00000000000000))*(x2168)*(x2171)))+(((IkReal(-1.00000000000000))*(x2169)*(x2172)))+(((x2171)*(x2172)))))));
9684 sj4array[0]=IKsin(j4array[0]);
9685 cj4array[0]=IKcos(j4array[0]);
9686 if( j4array[0] > IKPI )
9687 {
9688  j4array[0]-=IK2PI;
9689 }
9690 else if( j4array[0] < -IKPI )
9691 { j4array[0]+=IK2PI;
9692 }
9693 j4valid[0] = true;
9694 for(int ij4 = 0; ij4 < 1; ++ij4)
9695 {
9696 if( !j4valid[ij4] )
9697 {
9698  continue;
9699 }
9700 _ij4[0] = ij4; _ij4[1] = -1;
9701 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
9702 {
9703 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
9704 {
9705  j4valid[iij4]=false; _ij4[1] = iij4; break;
9706 }
9707 }
9708 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
9709 {
9710 IkReal evalcond[4];
9711 IkReal x2174=IKcos(j4);
9712 IkReal x2175=IKsin(j4);
9713 IkReal x2176=((IkReal(1.00000000000000))*(cj7));
9714 IkReal x2177=((cj8)*(r20));
9715 IkReal x2178=((cj3)*(r02));
9716 IkReal x2179=((IkReal(1.00000000000000))*(sj7));
9717 IkReal x2180=((sj3)*(sj7));
9718 IkReal x2181=((r21)*(sj8));
9719 IkReal x2182=((cj8)*(r10));
9720 IkReal x2183=((sj5)*(x2174));
9721 IkReal x2184=((cj5)*(x2175));
9722 IkReal x2185=((r11)*(sj3)*(sj8));
9723 IkReal x2186=((cj3)*(cj8)*(r00));
9724 IkReal x2187=((cj5)*(x2174));
9725 IkReal x2188=((cj3)*(r01)*(sj8));
9726 IkReal x2189=((sj5)*(x2175));
9727 IkReal x2190=((x2183)+(x2184));
9728 evalcond[0]=((((IkReal(-1.00000000000000))*(x2176)*(x2177)))+(x2189)+(((IkReal(-1.00000000000000))*(x2187)))+(((cj7)*(x2181)))+(((IkReal(-1.00000000000000))*(r22)*(x2179))));
9729 evalcond[1]=((x2190)+(((sj7)*(x2181)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x2177)*(x2179))));
9730 evalcond[2]=((((sj7)*(x2178)))+(x2190)+(((cj7)*(sj3)*(x2182)))+(((r12)*(x2180)))+(((IkReal(-1.00000000000000))*(x2176)*(x2188)))+(((IkReal(-1.00000000000000))*(x2176)*(x2185)))+(((cj7)*(x2186))));
9731 evalcond[3]=((((IkReal(-1.00000000000000))*(x2176)*(x2178)))+(((x2180)*(x2182)))+(x2187)+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2176)))+(((IkReal(-1.00000000000000))*(x2189)))+(((sj7)*(x2186)))+(((IkReal(-1.00000000000000))*(x2179)*(x2185)))+(((IkReal(-1.00000000000000))*(x2179)*(x2188))));
9732 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
9733 {
9734 continue;
9735 }
9736 }
9737 
9738 {
9739 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9740 vinfos[0].jointtype = 1;
9741 vinfos[0].foffset = j3;
9742 vinfos[0].indices[0] = _ij3[0];
9743 vinfos[0].indices[1] = _ij3[1];
9744 vinfos[0].maxsolutions = _nj3;
9745 vinfos[1].jointtype = 1;
9746 vinfos[1].foffset = j4;
9747 vinfos[1].indices[0] = _ij4[0];
9748 vinfos[1].indices[1] = _ij4[1];
9749 vinfos[1].maxsolutions = _nj4;
9750 vinfos[2].jointtype = 1;
9751 vinfos[2].foffset = j5;
9752 vinfos[2].indices[0] = _ij5[0];
9753 vinfos[2].indices[1] = _ij5[1];
9754 vinfos[2].maxsolutions = _nj5;
9755 vinfos[3].jointtype = 1;
9756 vinfos[3].foffset = j6;
9757 vinfos[3].indices[0] = _ij6[0];
9758 vinfos[3].indices[1] = _ij6[1];
9759 vinfos[3].maxsolutions = _nj6;
9760 vinfos[4].jointtype = 1;
9761 vinfos[4].foffset = j7;
9762 vinfos[4].indices[0] = _ij7[0];
9763 vinfos[4].indices[1] = _ij7[1];
9764 vinfos[4].maxsolutions = _nj7;
9765 vinfos[5].jointtype = 1;
9766 vinfos[5].foffset = j8;
9767 vinfos[5].indices[0] = _ij8[0];
9768 vinfos[5].indices[1] = _ij8[1];
9769 vinfos[5].maxsolutions = _nj8;
9770 std::vector<int> vfree(0);
9771 solutions.AddSolution(vinfos,vfree);
9772 }
9773 }
9774 }
9775 
9776 }
9777 
9778 }
9779 }
9780 }
9781 
9782 } else
9783 {
9784 IkReal x2191=((cj3)*(cj8));
9785 IkReal x2192=((r01)*(sj3));
9786 IkReal x2193=((r02)*(sj3));
9787 IkReal x2194=((IkReal(1.00000000000000))*(sj7));
9788 IkReal x2195=((IkReal(1.00000000000000))*(r11));
9789 IkReal x2196=((cj3)*(r12));
9790 IkReal x2197=((IkReal(1.00000000000000))*(cj7));
9791 IkReal x2198=((cj8)*(sj3));
9792 IkReal x2199=((sj3)*(sj8));
9793 IkReal x2200=((IkReal(1.00000000000000))*(cj3)*(sj8));
9794 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
9795 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
9796 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
9797 evalcond[3]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x2200)))+(((cj8)*(x2192)))+(((IkReal(-1.00000000000000))*(x2191)*(x2195)))+(((r00)*(x2199))));
9798 evalcond[4]=((((IkReal(-1.00000000000000))*(x2195)*(x2198)))+(((IkReal(-1.00000000000000))*(r10)*(x2199)))+(((IkReal(-1.00000000000000))*(r00)*(x2200)))+(((IkReal(-1.00000000000000))*(r01)*(x2191))));
9799 evalcond[5]=((((IkReal(-1.00000000000000))*(x2193)*(x2194)))+(((IkReal(-1.00000000000000))*(r00)*(x2197)*(x2198)))+(((sj7)*(x2196)))+(((cj7)*(sj8)*(x2192)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x2195)))+(((cj7)*(r10)*(x2191))));
9800 evalcond[6]=((((sj7)*(sj8)*(x2192)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x2194)))+(((IkReal(-1.00000000000000))*(x2196)*(x2197)))+(((IkReal(-1.00000000000000))*(r00)*(x2194)*(x2198)))+(((r10)*(sj7)*(x2191)))+(((cj7)*(x2193))));
9801 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
9802 {
9803 {
9804 IkReal j5array[1], cj5array[1], sj5array[1];
9805 bool j5valid[1]={false};
9806 _nj5 = 1;
9807 IkReal x2201=((IkReal(4.00000000000000))*(sj7));
9808 IkReal x2202=((npy)*(sj8));
9809 IkReal x2203=((IkReal(4.00000000000000))*(cj7));
9810 IkReal x2204=((cj8)*(npx));
9811 if( IKabs(((IkReal(0.120000000000000))+(((x2201)*(x2204)))+(((IkReal(-0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2201)*(x2202)))+(((IkReal(-1.00000000000000))*(npz)*(x2203))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((npz)*(x2201)))+(((x2203)*(x2204)))+(((IkReal(-1.00000000000000))*(x2202)*(x2203)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((x2201)*(x2204)))+(((IkReal(-0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2201)*(x2202)))+(((IkReal(-1.00000000000000))*(npz)*(x2203)))))+IKsqr(((IkReal(-0.940000000000000))+(((npz)*(x2201)))+(((x2203)*(x2204)))+(((IkReal(-1.00000000000000))*(x2202)*(x2203)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
9812  continue;
9813 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((x2201)*(x2204)))+(((IkReal(-0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2201)*(x2202)))+(((IkReal(-1.00000000000000))*(npz)*(x2203)))), ((IkReal(-0.940000000000000))+(((npz)*(x2201)))+(((x2203)*(x2204)))+(((IkReal(-1.00000000000000))*(x2202)*(x2203)))+(((IkReal(-0.360000000000000))*(cj7)))));
9814 sj5array[0]=IKsin(j5array[0]);
9815 cj5array[0]=IKcos(j5array[0]);
9816 if( j5array[0] > IKPI )
9817 {
9818  j5array[0]-=IK2PI;
9819 }
9820 else if( j5array[0] < -IKPI )
9821 { j5array[0]+=IK2PI;
9822 }
9823 j5valid[0] = true;
9824 for(int ij5 = 0; ij5 < 1; ++ij5)
9825 {
9826 if( !j5valid[ij5] )
9827 {
9828  continue;
9829 }
9830 _ij5[0] = ij5; _ij5[1] = -1;
9831 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9832 {
9833 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9834 {
9835  j5valid[iij5]=false; _ij5[1] = iij5; break;
9836 }
9837 }
9838 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9839 {
9840 IkReal evalcond[2];
9841 IkReal x2205=((IkReal(1.00000000000000))*(sj7));
9842 IkReal x2206=((npy)*(sj8));
9843 IkReal x2207=((cj8)*(npx));
9844 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2207)))+(((cj7)*(x2206)))+(((IkReal(-1.00000000000000))*(npz)*(x2205)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
9845 evalcond[1]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x2206)))+(((IkReal(-1.00000000000000))*(x2205)*(x2207)))+(((IkReal(0.250000000000000))*(IKsin(j5))))+(((cj7)*(npz))));
9846 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
9847 {
9848 continue;
9849 }
9850 }
9851 
9852 {
9853 IkReal dummyeval[1];
9854 IkReal gconst62;
9855 gconst62=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
9856 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
9857 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
9858 {
9859 {
9860 IkReal dummyeval[1];
9861 IkReal gconst63;
9862 gconst63=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
9863 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
9864 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
9865 {
9866 continue;
9867 
9868 } else
9869 {
9870 {
9871 IkReal j4array[1], cj4array[1], sj4array[1];
9872 bool j4valid[1]={false};
9873 _nj4 = 1;
9874 IkReal x2208=((cj3)*(cj5));
9875 IkReal x2209=((r02)*(sj7));
9876 IkReal x2210=((cj8)*(r00));
9877 IkReal x2211=((cj5)*(sj7));
9878 IkReal x2212=((cj5)*(sj3));
9879 IkReal x2213=((cj7)*(cj8));
9880 IkReal x2214=((IkReal(1.00000000000000))*(sj5));
9881 IkReal x2215=((r12)*(sj3));
9882 IkReal x2216=((sj3)*(sj5));
9883 IkReal x2217=((cj3)*(cj7)*(sj5));
9884 IkReal x2218=((IkReal(1.00000000000000))*(cj7)*(sj8));
9885 if( IKabs(((gconst63)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x2213)*(x2214)))+(((r10)*(x2212)*(x2213)))+(((IkReal(-1.00000000000000))*(r01)*(x2208)*(x2218)))+(((x2211)*(x2215)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2214)))+(((cj7)*(x2208)*(x2210)))+(((IkReal(-1.00000000000000))*(r11)*(x2212)*(x2218)))+(((x2208)*(x2209))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst63)*(((((x2210)*(x2217)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2218)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x2214)))+(((sj5)*(sj7)*(x2215)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2214)))+(((r22)*(x2211)))+(((cj5)*(r20)*(x2213)))+(((r10)*(x2213)*(x2216)))+(((cj3)*(sj5)*(x2209))))))) < IKFAST_ATAN2_MAGTHRESH )
9886  continue;
9887 j4array[0]=IKatan2(((gconst63)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x2213)*(x2214)))+(((r10)*(x2212)*(x2213)))+(((IkReal(-1.00000000000000))*(r01)*(x2208)*(x2218)))+(((x2211)*(x2215)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2214)))+(((cj7)*(x2208)*(x2210)))+(((IkReal(-1.00000000000000))*(r11)*(x2212)*(x2218)))+(((x2208)*(x2209)))))), ((gconst63)*(((((x2210)*(x2217)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2218)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x2214)))+(((sj5)*(sj7)*(x2215)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2214)))+(((r22)*(x2211)))+(((cj5)*(r20)*(x2213)))+(((r10)*(x2213)*(x2216)))+(((cj3)*(sj5)*(x2209)))))));
9888 sj4array[0]=IKsin(j4array[0]);
9889 cj4array[0]=IKcos(j4array[0]);
9890 if( j4array[0] > IKPI )
9891 {
9892  j4array[0]-=IK2PI;
9893 }
9894 else if( j4array[0] < -IKPI )
9895 { j4array[0]+=IK2PI;
9896 }
9897 j4valid[0] = true;
9898 for(int ij4 = 0; ij4 < 1; ++ij4)
9899 {
9900 if( !j4valid[ij4] )
9901 {
9902  continue;
9903 }
9904 _ij4[0] = ij4; _ij4[1] = -1;
9905 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
9906 {
9907 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
9908 {
9909  j4valid[iij4]=false; _ij4[1] = iij4; break;
9910 }
9911 }
9912 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
9913 {
9914 IkReal evalcond[4];
9915 IkReal x2219=IKcos(j4);
9916 IkReal x2220=IKsin(j4);
9917 IkReal x2221=((IkReal(1.00000000000000))*(cj7));
9918 IkReal x2222=((cj8)*(r20));
9919 IkReal x2223=((cj3)*(r02));
9920 IkReal x2224=((IkReal(1.00000000000000))*(sj7));
9921 IkReal x2225=((sj3)*(sj7));
9922 IkReal x2226=((r21)*(sj8));
9923 IkReal x2227=((IkReal(1.00000000000000))*(cj5));
9924 IkReal x2228=((cj8)*(r10));
9925 IkReal x2229=((sj5)*(x2220));
9926 IkReal x2230=((sj5)*(x2219));
9927 IkReal x2231=((r11)*(sj3)*(sj8));
9928 IkReal x2232=((cj3)*(cj8)*(r00));
9929 IkReal x2233=((cj3)*(r01)*(sj8));
9930 IkReal x2234=((x2219)*(x2227));
9931 evalcond[0]=((x2229)+(((cj7)*(x2226)))+(((IkReal(-1.00000000000000))*(x2221)*(x2222)))+(((IkReal(-1.00000000000000))*(x2234)))+(((IkReal(-1.00000000000000))*(r22)*(x2224))));
9932 evalcond[1]=((((IkReal(-1.00000000000000))*(x2222)*(x2224)))+(((IkReal(-1.00000000000000))*(x2220)*(x2227)))+(((sj7)*(x2226)))+(((IkReal(-1.00000000000000))*(x2230)))+(((cj7)*(r22))));
9933 evalcond[2]=((((r12)*(x2225)))+(x2230)+(((cj7)*(x2232)))+(((cj7)*(sj3)*(x2228)))+(((IkReal(-1.00000000000000))*(x2221)*(x2233)))+(((IkReal(-1.00000000000000))*(x2221)*(x2231)))+(((cj5)*(x2220)))+(((sj7)*(x2223))));
9934 evalcond[3]=((x2229)+(((IkReal(-1.00000000000000))*(x2224)*(x2233)))+(((IkReal(-1.00000000000000))*(x2224)*(x2231)))+(((x2225)*(x2228)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2221)))+(((IkReal(-1.00000000000000))*(x2221)*(x2223)))+(((sj7)*(x2232)))+(((IkReal(-1.00000000000000))*(x2234))));
9935 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
9936 {
9937 continue;
9938 }
9939 }
9940 
9941 {
9942 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9943 vinfos[0].jointtype = 1;
9944 vinfos[0].foffset = j3;
9945 vinfos[0].indices[0] = _ij3[0];
9946 vinfos[0].indices[1] = _ij3[1];
9947 vinfos[0].maxsolutions = _nj3;
9948 vinfos[1].jointtype = 1;
9949 vinfos[1].foffset = j4;
9950 vinfos[1].indices[0] = _ij4[0];
9951 vinfos[1].indices[1] = _ij4[1];
9952 vinfos[1].maxsolutions = _nj4;
9953 vinfos[2].jointtype = 1;
9954 vinfos[2].foffset = j5;
9955 vinfos[2].indices[0] = _ij5[0];
9956 vinfos[2].indices[1] = _ij5[1];
9957 vinfos[2].maxsolutions = _nj5;
9958 vinfos[3].jointtype = 1;
9959 vinfos[3].foffset = j6;
9960 vinfos[3].indices[0] = _ij6[0];
9961 vinfos[3].indices[1] = _ij6[1];
9962 vinfos[3].maxsolutions = _nj6;
9963 vinfos[4].jointtype = 1;
9964 vinfos[4].foffset = j7;
9965 vinfos[4].indices[0] = _ij7[0];
9966 vinfos[4].indices[1] = _ij7[1];
9967 vinfos[4].maxsolutions = _nj7;
9968 vinfos[5].jointtype = 1;
9969 vinfos[5].foffset = j8;
9970 vinfos[5].indices[0] = _ij8[0];
9971 vinfos[5].indices[1] = _ij8[1];
9972 vinfos[5].maxsolutions = _nj8;
9973 std::vector<int> vfree(0);
9974 solutions.AddSolution(vinfos,vfree);
9975 }
9976 }
9977 }
9978 
9979 }
9980 
9981 }
9982 
9983 } else
9984 {
9985 {
9986 IkReal j4array[1], cj4array[1], sj4array[1];
9987 bool j4valid[1]={false};
9988 _nj4 = 1;
9989 IkReal x2235=((cj7)*(sj5));
9990 IkReal x2236=((r21)*(sj8));
9991 IkReal x2237=((cj5)*(cj7));
9992 IkReal x2238=((cj8)*(r20));
9993 IkReal x2239=((sj5)*(sj7));
9994 IkReal x2240=((IkReal(1.00000000000000))*(cj5)*(sj7));
9995 if( IKabs(((gconst62)*(((((x2235)*(x2238)))+(((r22)*(x2239)))+(((r22)*(x2237)))+(((cj5)*(sj7)*(x2236)))+(((IkReal(-1.00000000000000))*(x2238)*(x2240)))+(((IkReal(-1.00000000000000))*(x2235)*(x2236))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst62)*(((((IkReal(-1.00000000000000))*(x2237)*(x2238)))+(((r22)*(x2235)))+(((IkReal(-1.00000000000000))*(r22)*(x2240)))+(((x2236)*(x2239)))+(((x2236)*(x2237)))+(((IkReal(-1.00000000000000))*(x2238)*(x2239))))))) < IKFAST_ATAN2_MAGTHRESH )
9996  continue;
9997 j4array[0]=IKatan2(((gconst62)*(((((x2235)*(x2238)))+(((r22)*(x2239)))+(((r22)*(x2237)))+(((cj5)*(sj7)*(x2236)))+(((IkReal(-1.00000000000000))*(x2238)*(x2240)))+(((IkReal(-1.00000000000000))*(x2235)*(x2236)))))), ((gconst62)*(((((IkReal(-1.00000000000000))*(x2237)*(x2238)))+(((r22)*(x2235)))+(((IkReal(-1.00000000000000))*(r22)*(x2240)))+(((x2236)*(x2239)))+(((x2236)*(x2237)))+(((IkReal(-1.00000000000000))*(x2238)*(x2239)))))));
9998 sj4array[0]=IKsin(j4array[0]);
9999 cj4array[0]=IKcos(j4array[0]);
10000 if( j4array[0] > IKPI )
10001 {
10002  j4array[0]-=IK2PI;
10003 }
10004 else if( j4array[0] < -IKPI )
10005 { j4array[0]+=IK2PI;
10006 }
10007 j4valid[0] = true;
10008 for(int ij4 = 0; ij4 < 1; ++ij4)
10009 {
10010 if( !j4valid[ij4] )
10011 {
10012  continue;
10013 }
10014 _ij4[0] = ij4; _ij4[1] = -1;
10015 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10016 {
10017 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10018 {
10019  j4valid[iij4]=false; _ij4[1] = iij4; break;
10020 }
10021 }
10022 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10023 {
10024 IkReal evalcond[4];
10025 IkReal x2241=IKcos(j4);
10026 IkReal x2242=IKsin(j4);
10027 IkReal x2243=((IkReal(1.00000000000000))*(cj7));
10028 IkReal x2244=((cj8)*(r20));
10029 IkReal x2245=((cj3)*(r02));
10030 IkReal x2246=((IkReal(1.00000000000000))*(sj7));
10031 IkReal x2247=((sj3)*(sj7));
10032 IkReal x2248=((r21)*(sj8));
10033 IkReal x2249=((IkReal(1.00000000000000))*(cj5));
10034 IkReal x2250=((cj8)*(r10));
10035 IkReal x2251=((sj5)*(x2242));
10036 IkReal x2252=((sj5)*(x2241));
10037 IkReal x2253=((r11)*(sj3)*(sj8));
10038 IkReal x2254=((cj3)*(cj8)*(r00));
10039 IkReal x2255=((cj3)*(r01)*(sj8));
10040 IkReal x2256=((x2241)*(x2249));
10041 evalcond[0]=((((cj7)*(x2248)))+(x2251)+(((IkReal(-1.00000000000000))*(r22)*(x2246)))+(((IkReal(-1.00000000000000))*(x2256)))+(((IkReal(-1.00000000000000))*(x2243)*(x2244))));
10042 evalcond[1]=((((IkReal(-1.00000000000000))*(x2252)))+(((IkReal(-1.00000000000000))*(x2244)*(x2246)))+(((IkReal(-1.00000000000000))*(x2242)*(x2249)))+(((sj7)*(x2248)))+(((cj7)*(r22))));
10043 evalcond[2]=((((cj7)*(x2254)))+(x2252)+(((cj7)*(sj3)*(x2250)))+(((IkReal(-1.00000000000000))*(x2243)*(x2255)))+(((IkReal(-1.00000000000000))*(x2243)*(x2253)))+(((cj5)*(x2242)))+(((sj7)*(x2245)))+(((r12)*(x2247))));
10044 evalcond[3]=((x2251)+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2243)))+(((IkReal(-1.00000000000000))*(x2256)))+(((x2247)*(x2250)))+(((sj7)*(x2254)))+(((IkReal(-1.00000000000000))*(x2243)*(x2245)))+(((IkReal(-1.00000000000000))*(x2246)*(x2253)))+(((IkReal(-1.00000000000000))*(x2246)*(x2255))));
10045 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
10046 {
10047 continue;
10048 }
10049 }
10050 
10051 {
10052 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10053 vinfos[0].jointtype = 1;
10054 vinfos[0].foffset = j3;
10055 vinfos[0].indices[0] = _ij3[0];
10056 vinfos[0].indices[1] = _ij3[1];
10057 vinfos[0].maxsolutions = _nj3;
10058 vinfos[1].jointtype = 1;
10059 vinfos[1].foffset = j4;
10060 vinfos[1].indices[0] = _ij4[0];
10061 vinfos[1].indices[1] = _ij4[1];
10062 vinfos[1].maxsolutions = _nj4;
10063 vinfos[2].jointtype = 1;
10064 vinfos[2].foffset = j5;
10065 vinfos[2].indices[0] = _ij5[0];
10066 vinfos[2].indices[1] = _ij5[1];
10067 vinfos[2].maxsolutions = _nj5;
10068 vinfos[3].jointtype = 1;
10069 vinfos[3].foffset = j6;
10070 vinfos[3].indices[0] = _ij6[0];
10071 vinfos[3].indices[1] = _ij6[1];
10072 vinfos[3].maxsolutions = _nj6;
10073 vinfos[4].jointtype = 1;
10074 vinfos[4].foffset = j7;
10075 vinfos[4].indices[0] = _ij7[0];
10076 vinfos[4].indices[1] = _ij7[1];
10077 vinfos[4].maxsolutions = _nj7;
10078 vinfos[5].jointtype = 1;
10079 vinfos[5].foffset = j8;
10080 vinfos[5].indices[0] = _ij8[0];
10081 vinfos[5].indices[1] = _ij8[1];
10082 vinfos[5].maxsolutions = _nj8;
10083 std::vector<int> vfree(0);
10084 solutions.AddSolution(vinfos,vfree);
10085 }
10086 }
10087 }
10088 
10089 }
10090 
10091 }
10092 }
10093 }
10094 
10095 } else
10096 {
10097 if( 1 )
10098 {
10099 continue;
10100 
10101 } else
10102 {
10103 }
10104 }
10105 }
10106 }
10107 }
10108 }
10109 
10110 } else
10111 {
10112 {
10113 IkReal j5array[1], cj5array[1], sj5array[1];
10114 bool j5valid[1]={false};
10115 _nj5 = 1;
10116 IkReal x2257=((IkReal(4.00000000000000))*(cj7));
10117 IkReal x2258=((cj8)*(npx));
10118 IkReal x2259=((IkReal(4.00000000000000))*(sj7));
10119 IkReal x2260=((IkReal(4.00000000000000))*(npy)*(sj8));
10120 if( IKabs(((((IKabs(cj6) != 0)?((IkReal)1/(cj6)):(IkReal)1.0e30))*(((((IkReal(0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2258)*(x2259)))+(((npy)*(sj8)*(x2259)))+(((IkReal(-0.380000000000000))*(sj6)))+(((npz)*(x2257)))+(((IkReal(0.120000000000000))*(cj6))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(npy)*(sj8)*(x2257)))+(((npz)*(x2259)))+(((x2257)*(x2258)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj6) != 0)?((IkReal)1/(cj6)):(IkReal)1.0e30))*(((((IkReal(0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2258)*(x2259)))+(((npy)*(sj8)*(x2259)))+(((IkReal(-0.380000000000000))*(sj6)))+(((npz)*(x2257)))+(((IkReal(0.120000000000000))*(cj6)))))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(npy)*(sj8)*(x2257)))+(((npz)*(x2259)))+(((x2257)*(x2258)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
10121  continue;
10122 j5array[0]=IKatan2(((((IKabs(cj6) != 0)?((IkReal)1/(cj6)):(IkReal)1.0e30))*(((((IkReal(0.360000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2258)*(x2259)))+(((npy)*(sj8)*(x2259)))+(((IkReal(-0.380000000000000))*(sj6)))+(((npz)*(x2257)))+(((IkReal(0.120000000000000))*(cj6)))))), ((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(npy)*(sj8)*(x2257)))+(((npz)*(x2259)))+(((x2257)*(x2258)))+(((IkReal(-0.360000000000000))*(cj7)))));
10123 sj5array[0]=IKsin(j5array[0]);
10124 cj5array[0]=IKcos(j5array[0]);
10125 if( j5array[0] > IKPI )
10126 {
10127  j5array[0]-=IK2PI;
10128 }
10129 else if( j5array[0] < -IKPI )
10130 { j5array[0]+=IK2PI;
10131 }
10132 j5valid[0] = true;
10133 for(int ij5 = 0; ij5 < 1; ++ij5)
10134 {
10135 if( !j5valid[ij5] )
10136 {
10137  continue;
10138 }
10139 _ij5[0] = ij5; _ij5[1] = -1;
10140 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
10141 {
10142 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10143 {
10144  j5valid[iij5]=false; _ij5[1] = iij5; break;
10145 }
10146 }
10147 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10148 {
10149 IkReal evalcond[3];
10150 IkReal x2261=IKsin(j5);
10151 IkReal x2262=((IkReal(1.00000000000000))*(sj7));
10152 IkReal x2263=((npy)*(sj8));
10153 IkReal x2264=((cj8)*(npx));
10154 IkReal x2265=((IkReal(0.250000000000000))*(x2261));
10155 evalcond[0]=((((IkReal(-0.0300000000000000))*(sj6)))+(((IkReal(-0.0950000000000000))*(cj6)))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((sj6)*(x2265))));
10156 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x2262)))+(((IkReal(0.0900000000000000))*(cj7)))+(((cj7)*(x2263)))+(((IkReal(-1.00000000000000))*(cj7)*(x2264)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
10157 evalcond[2]=((((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x2263)))+(((IkReal(0.0300000000000000))*(cj6)))+(((IkReal(-0.0950000000000000))*(sj6)))+(((cj7)*(npz)))+(((IkReal(-1.00000000000000))*(x2262)*(x2264)))+(((IkReal(-1.00000000000000))*(cj6)*(x2265))));
10158 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
10159 {
10160 continue;
10161 }
10162 }
10163 
10164 {
10165 IkReal dummyeval[1];
10166 IkReal gconst46;
10167 gconst46=IKsign(((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5))))));
10168 dummyeval[0]=((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5)))));
10169 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10170 {
10171 {
10172 IkReal dummyeval[1];
10173 IkReal gconst47;
10174 gconst47=IKsign(((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5))))));
10175 dummyeval[0]=((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5)))));
10176 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10177 {
10178 {
10179 IkReal evalcond[9];
10180 IkReal x2266=((IkReal(1.00000000000000))*(sj7));
10181 IkReal x2267=((IkReal(1.00000000000000))*(cj3));
10182 IkReal x2268=((cj7)*(r02));
10183 IkReal x2269=((cj8)*(r00));
10184 IkReal x2270=((cj3)*(sj7));
10185 IkReal x2271=((cj8)*(npx));
10186 IkReal x2272=((r01)*(sj3));
10187 IkReal x2273=((cj7)*(sj8));
10188 IkReal x2274=((r11)*(sj8));
10189 IkReal x2275=((IkReal(1.00000000000000))*(cj7));
10190 IkReal x2276=((sj7)*(sj8));
10191 IkReal x2277=((cj8)*(r10));
10192 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
10193 evalcond[1]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(sj5))));
10194 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x2266)))+(((IkReal(0.0900000000000000))*(cj7)))+(((npy)*(x2273)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(x2271)*(x2275))));
10195 evalcond[3]=((((cj8)*(x2272)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2267)))+(((r00)*(sj3)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2267))));
10196 evalcond[4]=((((r21)*(x2276)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x2266)))+(((cj7)*(r22))));
10197 evalcond[5]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2266)*(x2271)))+(((npy)*(x2276)))+(((cj7)*(npz))));
10198 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(sj3)*(x2266)))+(((cj3)*(cj7)*(x2277)))+(((IkReal(-1.00000000000000))*(r11)*(x2267)*(x2273)))+(((IkReal(-1.00000000000000))*(sj3)*(x2269)*(x2275)))+(((x2272)*(x2273)))+(((r12)*(x2270))));
10199 evalcond[7]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x2267)))+(((x2270)*(x2277)))+(((IkReal(-1.00000000000000))*(sj3)*(x2266)*(x2269)))+(((x2272)*(x2276)))+(((sj3)*(x2268)))+(((IkReal(-1.00000000000000))*(cj3)*(x2266)*(x2274))));
10200 evalcond[8]=((((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x2266)))+(((x2269)*(x2270)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2275)))+(((IkReal(-1.00000000000000))*(sj3)*(x2266)*(x2274)))+(((sj3)*(sj7)*(x2277)))+(((IkReal(-1.00000000000000))*(x2267)*(x2268))));
10201 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
10202 {
10203 {
10204 IkReal dummyeval[1];
10205 IkReal gconst48;
10206 gconst48=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
10207 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
10208 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10209 {
10210 {
10211 IkReal dummyeval[1];
10212 IkReal gconst49;
10213 gconst49=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
10214 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
10215 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10216 {
10217 continue;
10218 
10219 } else
10220 {
10221 {
10222 IkReal j4array[1], cj4array[1], sj4array[1];
10223 bool j4valid[1]={false};
10224 _nj4 = 1;
10225 IkReal x2278=((cj8)*(sj5));
10226 IkReal x2279=((cj3)*(r01));
10227 IkReal x2280=((IkReal(1.00000000000000))*(cj5));
10228 IkReal x2281=((r11)*(sj3));
10229 IkReal x2282=((sj5)*(sj8));
10230 IkReal x2283=((r10)*(sj3));
10231 IkReal x2284=((cj3)*(r00)*(sj8));
10232 if( IKabs(((gconst49)*(((((x2282)*(x2283)))+(((cj5)*(r20)*(sj8)))+(((cj3)*(r00)*(x2282)))+(((x2278)*(x2281)))+(((cj5)*(cj8)*(r21)))+(((x2278)*(x2279))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((IkReal(-1.00000000000000))*(x2280)*(x2284)))+(((r21)*(x2278)))+(((r20)*(x2282)))+(((IkReal(-1.00000000000000))*(sj8)*(x2280)*(x2283)))+(((IkReal(-1.00000000000000))*(cj8)*(x2280)*(x2281)))+(((IkReal(-1.00000000000000))*(cj8)*(x2279)*(x2280))))))) < IKFAST_ATAN2_MAGTHRESH )
10233  continue;
10234 j4array[0]=IKatan2(((gconst49)*(((((x2282)*(x2283)))+(((cj5)*(r20)*(sj8)))+(((cj3)*(r00)*(x2282)))+(((x2278)*(x2281)))+(((cj5)*(cj8)*(r21)))+(((x2278)*(x2279)))))), ((gconst49)*(((((IkReal(-1.00000000000000))*(x2280)*(x2284)))+(((r21)*(x2278)))+(((r20)*(x2282)))+(((IkReal(-1.00000000000000))*(sj8)*(x2280)*(x2283)))+(((IkReal(-1.00000000000000))*(cj8)*(x2280)*(x2281)))+(((IkReal(-1.00000000000000))*(cj8)*(x2279)*(x2280)))))));
10235 sj4array[0]=IKsin(j4array[0]);
10236 cj4array[0]=IKcos(j4array[0]);
10237 if( j4array[0] > IKPI )
10238 {
10239  j4array[0]-=IK2PI;
10240 }
10241 else if( j4array[0] < -IKPI )
10242 { j4array[0]+=IK2PI;
10243 }
10244 j4valid[0] = true;
10245 for(int ij4 = 0; ij4 < 1; ++ij4)
10246 {
10247 if( !j4valid[ij4] )
10248 {
10249  continue;
10250 }
10251 _ij4[0] = ij4; _ij4[1] = -1;
10252 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10253 {
10254 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10255 {
10256  j4valid[iij4]=false; _ij4[1] = iij4; break;
10257 }
10258 }
10259 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10260 {
10261 IkReal evalcond[4];
10262 IkReal x2285=IKsin(j4);
10263 IkReal x2286=IKcos(j4);
10264 IkReal x2287=((IkReal(1.00000000000000))*(cj8));
10265 IkReal x2288=((cj3)*(r01));
10266 IkReal x2289=((cj3)*(r00));
10267 IkReal x2290=((cj7)*(cj8));
10268 IkReal x2291=((IkReal(1.00000000000000))*(cj5));
10269 IkReal x2292=((IkReal(1.00000000000000))*(sj8));
10270 IkReal x2293=((r11)*(sj3));
10271 IkReal x2294=((r10)*(sj3));
10272 IkReal x2295=((sj5)*(x2285));
10273 IkReal x2296=((sj5)*(x2286));
10274 IkReal x2297=((x2286)*(x2291));
10275 evalcond[0]=((((IkReal(-1.00000000000000))*(x2285)*(x2291)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2296)))+(((r20)*(sj8))));
10276 evalcond[1]=((x2295)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2287)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x2297)))+(((cj7)*(r21)*(sj8))));
10277 evalcond[2]=((((IkReal(-1.00000000000000))*(x2289)*(x2292)))+(x2295)+(((IkReal(-1.00000000000000))*(x2292)*(x2294)))+(((IkReal(-1.00000000000000))*(x2287)*(x2293)))+(((IkReal(-1.00000000000000))*(x2287)*(x2288)))+(((IkReal(-1.00000000000000))*(x2297))));
10278 evalcond[3]=((((r12)*(sj3)*(sj7)))+(x2296)+(((IkReal(-1.00000000000000))*(cj7)*(x2288)*(x2292)))+(((IkReal(-1.00000000000000))*(cj7)*(x2292)*(x2293)))+(((x2289)*(x2290)))+(((cj3)*(r02)*(sj7)))+(((cj5)*(x2285)))+(((x2290)*(x2294))));
10279 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
10280 {
10281 continue;
10282 }
10283 }
10284 
10285 {
10286 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10287 vinfos[0].jointtype = 1;
10288 vinfos[0].foffset = j3;
10289 vinfos[0].indices[0] = _ij3[0];
10290 vinfos[0].indices[1] = _ij3[1];
10291 vinfos[0].maxsolutions = _nj3;
10292 vinfos[1].jointtype = 1;
10293 vinfos[1].foffset = j4;
10294 vinfos[1].indices[0] = _ij4[0];
10295 vinfos[1].indices[1] = _ij4[1];
10296 vinfos[1].maxsolutions = _nj4;
10297 vinfos[2].jointtype = 1;
10298 vinfos[2].foffset = j5;
10299 vinfos[2].indices[0] = _ij5[0];
10300 vinfos[2].indices[1] = _ij5[1];
10301 vinfos[2].maxsolutions = _nj5;
10302 vinfos[3].jointtype = 1;
10303 vinfos[3].foffset = j6;
10304 vinfos[3].indices[0] = _ij6[0];
10305 vinfos[3].indices[1] = _ij6[1];
10306 vinfos[3].maxsolutions = _nj6;
10307 vinfos[4].jointtype = 1;
10308 vinfos[4].foffset = j7;
10309 vinfos[4].indices[0] = _ij7[0];
10310 vinfos[4].indices[1] = _ij7[1];
10311 vinfos[4].maxsolutions = _nj7;
10312 vinfos[5].jointtype = 1;
10313 vinfos[5].foffset = j8;
10314 vinfos[5].indices[0] = _ij8[0];
10315 vinfos[5].indices[1] = _ij8[1];
10316 vinfos[5].maxsolutions = _nj8;
10317 std::vector<int> vfree(0);
10318 solutions.AddSolution(vinfos,vfree);
10319 }
10320 }
10321 }
10322 
10323 }
10324 
10325 }
10326 
10327 } else
10328 {
10329 {
10330 IkReal j4array[1], cj4array[1], sj4array[1];
10331 bool j4valid[1]={false};
10332 _nj4 = 1;
10333 IkReal x2298=((sj5)*(sj8));
10334 IkReal x2299=((IkReal(1.00000000000000))*(cj7));
10335 IkReal x2300=((r22)*(sj7));
10336 IkReal x2301=((cj8)*(sj5));
10337 IkReal x2302=((cj5)*(cj8));
10338 IkReal x2303=((cj5)*(sj8));
10339 if( IKabs(((gconst48)*(((((cj7)*(r20)*(x2301)))+(((r20)*(x2303)))+(((sj5)*(x2300)))+(((IkReal(-1.00000000000000))*(r21)*(x2298)*(x2299)))+(((r21)*(x2302))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((IkReal(-1.00000000000000))*(cj5)*(x2300)))+(((cj7)*(r21)*(x2303)))+(((r20)*(x2298)))+(((r21)*(x2301)))+(((IkReal(-1.00000000000000))*(r20)*(x2299)*(x2302))))))) < IKFAST_ATAN2_MAGTHRESH )
10340  continue;
10341 j4array[0]=IKatan2(((gconst48)*(((((cj7)*(r20)*(x2301)))+(((r20)*(x2303)))+(((sj5)*(x2300)))+(((IkReal(-1.00000000000000))*(r21)*(x2298)*(x2299)))+(((r21)*(x2302)))))), ((gconst48)*(((((IkReal(-1.00000000000000))*(cj5)*(x2300)))+(((cj7)*(r21)*(x2303)))+(((r20)*(x2298)))+(((r21)*(x2301)))+(((IkReal(-1.00000000000000))*(r20)*(x2299)*(x2302)))))));
10342 sj4array[0]=IKsin(j4array[0]);
10343 cj4array[0]=IKcos(j4array[0]);
10344 if( j4array[0] > IKPI )
10345 {
10346  j4array[0]-=IK2PI;
10347 }
10348 else if( j4array[0] < -IKPI )
10349 { j4array[0]+=IK2PI;
10350 }
10351 j4valid[0] = true;
10352 for(int ij4 = 0; ij4 < 1; ++ij4)
10353 {
10354 if( !j4valid[ij4] )
10355 {
10356  continue;
10357 }
10358 _ij4[0] = ij4; _ij4[1] = -1;
10359 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10360 {
10361 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10362 {
10363  j4valid[iij4]=false; _ij4[1] = iij4; break;
10364 }
10365 }
10366 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10367 {
10368 IkReal evalcond[4];
10369 IkReal x2304=IKsin(j4);
10370 IkReal x2305=IKcos(j4);
10371 IkReal x2306=((IkReal(1.00000000000000))*(cj8));
10372 IkReal x2307=((cj3)*(r01));
10373 IkReal x2308=((cj3)*(r00));
10374 IkReal x2309=((cj7)*(cj8));
10375 IkReal x2310=((IkReal(1.00000000000000))*(cj5));
10376 IkReal x2311=((IkReal(1.00000000000000))*(sj8));
10377 IkReal x2312=((r11)*(sj3));
10378 IkReal x2313=((r10)*(sj3));
10379 IkReal x2314=((sj5)*(x2304));
10380 IkReal x2315=((sj5)*(x2305));
10381 IkReal x2316=((x2305)*(x2310));
10382 evalcond[0]=((((IkReal(-1.00000000000000))*(x2315)))+(((IkReal(-1.00000000000000))*(x2304)*(x2310)))+(((cj8)*(r21)))+(((r20)*(sj8))));
10383 evalcond[1]=((x2314)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2306)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(x2316))));
10384 evalcond[2]=((((IkReal(-1.00000000000000))*(x2306)*(x2307)))+(((IkReal(-1.00000000000000))*(x2311)*(x2313)))+(x2314)+(((IkReal(-1.00000000000000))*(x2308)*(x2311)))+(((IkReal(-1.00000000000000))*(x2306)*(x2312)))+(((IkReal(-1.00000000000000))*(x2316))));
10385 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2311)*(x2312)))+(((x2308)*(x2309)))+(x2315)+(((cj5)*(x2304)))+(((x2309)*(x2313)))+(((IkReal(-1.00000000000000))*(cj7)*(x2307)*(x2311)))+(((cj3)*(r02)*(sj7))));
10386 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
10387 {
10388 continue;
10389 }
10390 }
10391 
10392 {
10393 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10394 vinfos[0].jointtype = 1;
10395 vinfos[0].foffset = j3;
10396 vinfos[0].indices[0] = _ij3[0];
10397 vinfos[0].indices[1] = _ij3[1];
10398 vinfos[0].maxsolutions = _nj3;
10399 vinfos[1].jointtype = 1;
10400 vinfos[1].foffset = j4;
10401 vinfos[1].indices[0] = _ij4[0];
10402 vinfos[1].indices[1] = _ij4[1];
10403 vinfos[1].maxsolutions = _nj4;
10404 vinfos[2].jointtype = 1;
10405 vinfos[2].foffset = j5;
10406 vinfos[2].indices[0] = _ij5[0];
10407 vinfos[2].indices[1] = _ij5[1];
10408 vinfos[2].maxsolutions = _nj5;
10409 vinfos[3].jointtype = 1;
10410 vinfos[3].foffset = j6;
10411 vinfos[3].indices[0] = _ij6[0];
10412 vinfos[3].indices[1] = _ij6[1];
10413 vinfos[3].maxsolutions = _nj6;
10414 vinfos[4].jointtype = 1;
10415 vinfos[4].foffset = j7;
10416 vinfos[4].indices[0] = _ij7[0];
10417 vinfos[4].indices[1] = _ij7[1];
10418 vinfos[4].maxsolutions = _nj7;
10419 vinfos[5].jointtype = 1;
10420 vinfos[5].foffset = j8;
10421 vinfos[5].indices[0] = _ij8[0];
10422 vinfos[5].indices[1] = _ij8[1];
10423 vinfos[5].maxsolutions = _nj8;
10424 std::vector<int> vfree(0);
10425 solutions.AddSolution(vinfos,vfree);
10426 }
10427 }
10428 }
10429 
10430 }
10431 
10432 }
10433 
10434 } else
10435 {
10436 IkReal x2317=((IkReal(1.00000000000000))*(sj7));
10437 IkReal x2318=((IkReal(1.00000000000000))*(cj3));
10438 IkReal x2319=((cj7)*(r02));
10439 IkReal x2320=((cj8)*(r00));
10440 IkReal x2321=((cj3)*(sj7));
10441 IkReal x2322=((cj8)*(npx));
10442 IkReal x2323=((r01)*(sj3));
10443 IkReal x2324=((cj7)*(sj8));
10444 IkReal x2325=((r11)*(sj8));
10445 IkReal x2326=((IkReal(1.00000000000000))*(cj7));
10446 IkReal x2327=((sj7)*(sj8));
10447 IkReal x2328=((cj8)*(r10));
10448 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
10449 evalcond[1]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(sj5))));
10450 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((npy)*(x2324)))+(((IkReal(-1.00000000000000))*(x2322)*(x2326)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x2317))));
10451 evalcond[3]=((((cj8)*(x2323)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2318)))+(((r00)*(sj3)*(sj8)))+(((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2318))));
10452 evalcond[4]=((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x2317)))+(((r21)*(x2327)))+(((cj7)*(r22))));
10453 evalcond[5]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x2327)))+(((IkReal(-1.00000000000000))*(x2317)*(x2322)))+(((cj7)*(npz))));
10454 evalcond[6]=((((cj3)*(cj7)*(x2328)))+(((IkReal(-1.00000000000000))*(r11)*(x2318)*(x2324)))+(((r12)*(x2321)))+(((x2323)*(x2324)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x2317)))+(((IkReal(-1.00000000000000))*(sj3)*(x2320)*(x2326))));
10455 evalcond[7]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x2317)*(x2325)))+(((sj3)*(x2319)))+(((x2321)*(x2328)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x2318)))+(((IkReal(-1.00000000000000))*(sj3)*(x2317)*(x2320)))+(((x2323)*(x2327))));
10456 evalcond[8]=((((IkReal(-1.00000000000000))*(x2318)*(x2319)))+(((x2320)*(x2321)))+(((IkReal(-1.00000000000000))*(sj3)*(x2317)*(x2325)))+(((sj3)*(sj7)*(x2328)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x2317)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2326))));
10457 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
10458 {
10459 {
10460 IkReal dummyeval[1];
10461 IkReal gconst50;
10462 gconst50=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
10463 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
10464 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10465 {
10466 {
10467 IkReal dummyeval[1];
10468 IkReal gconst51;
10469 gconst51=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
10470 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
10471 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10472 {
10473 continue;
10474 
10475 } else
10476 {
10477 {
10478 IkReal j4array[1], cj4array[1], sj4array[1];
10479 bool j4valid[1]={false};
10480 _nj4 = 1;
10481 IkReal x2329=((IkReal(1.00000000000000))*(sj5));
10482 IkReal x2330=((r20)*(sj8));
10483 IkReal x2331=((cj5)*(cj8));
10484 IkReal x2332=((r11)*(sj3));
10485 IkReal x2333=((cj3)*(r01));
10486 IkReal x2334=((cj3)*(r00)*(sj8));
10487 IkReal x2335=((r10)*(sj3)*(sj8));
10488 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(r21)*(x2331)))+(((IkReal(-1.00000000000000))*(cj5)*(x2330)))+(((IkReal(-1.00000000000000))*(cj8)*(x2329)*(x2333)))+(((IkReal(-1.00000000000000))*(cj8)*(x2329)*(x2332)))+(((IkReal(-1.00000000000000))*(x2329)*(x2334)))+(((IkReal(-1.00000000000000))*(x2329)*(x2335))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((x2331)*(x2332)))+(((x2331)*(x2333)))+(((IkReal(-1.00000000000000))*(x2329)*(x2330)))+(((cj5)*(x2334)))+(((cj5)*(x2335)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2329))))))) < IKFAST_ATAN2_MAGTHRESH )
10489  continue;
10490 j4array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(r21)*(x2331)))+(((IkReal(-1.00000000000000))*(cj5)*(x2330)))+(((IkReal(-1.00000000000000))*(cj8)*(x2329)*(x2333)))+(((IkReal(-1.00000000000000))*(cj8)*(x2329)*(x2332)))+(((IkReal(-1.00000000000000))*(x2329)*(x2334)))+(((IkReal(-1.00000000000000))*(x2329)*(x2335)))))), ((gconst51)*(((((x2331)*(x2332)))+(((x2331)*(x2333)))+(((IkReal(-1.00000000000000))*(x2329)*(x2330)))+(((cj5)*(x2334)))+(((cj5)*(x2335)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2329)))))));
10491 sj4array[0]=IKsin(j4array[0]);
10492 cj4array[0]=IKcos(j4array[0]);
10493 if( j4array[0] > IKPI )
10494 {
10495  j4array[0]-=IK2PI;
10496 }
10497 else if( j4array[0] < -IKPI )
10498 { j4array[0]+=IK2PI;
10499 }
10500 j4valid[0] = true;
10501 for(int ij4 = 0; ij4 < 1; ++ij4)
10502 {
10503 if( !j4valid[ij4] )
10504 {
10505  continue;
10506 }
10507 _ij4[0] = ij4; _ij4[1] = -1;
10508 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10509 {
10510 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10511 {
10512  j4valid[iij4]=false; _ij4[1] = iij4; break;
10513 }
10514 }
10515 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10516 {
10517 IkReal evalcond[4];
10518 IkReal x2336=IKsin(j4);
10519 IkReal x2337=IKcos(j4);
10520 IkReal x2338=((IkReal(1.00000000000000))*(cj8));
10521 IkReal x2339=((cj3)*(r01));
10522 IkReal x2340=((cj3)*(r00));
10523 IkReal x2341=((cj7)*(cj8));
10524 IkReal x2342=((r11)*(sj3));
10525 IkReal x2343=((IkReal(1.00000000000000))*(sj8));
10526 IkReal x2344=((r10)*(sj3));
10527 IkReal x2345=((sj5)*(x2337));
10528 IkReal x2346=((cj5)*(x2336));
10529 IkReal x2347=((cj5)*(x2337));
10530 IkReal x2348=((sj5)*(x2336));
10531 IkReal x2349=((x2345)+(x2346));
10532 evalcond[0]=((x2349)+(((cj8)*(r21)))+(((r20)*(sj8))));
10533 evalcond[1]=((x2348)+(((IkReal(-1.00000000000000))*(x2347)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2338)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
10534 evalcond[2]=((((IkReal(-1.00000000000000))*(x2340)*(x2343)))+(x2347)+(((IkReal(-1.00000000000000))*(x2348)))+(((IkReal(-1.00000000000000))*(x2338)*(x2339)))+(((IkReal(-1.00000000000000))*(x2343)*(x2344)))+(((IkReal(-1.00000000000000))*(x2338)*(x2342))));
10535 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x2340)*(x2341)))+(x2349)+(((x2341)*(x2344)))+(((IkReal(-1.00000000000000))*(cj7)*(x2339)*(x2343)))+(((IkReal(-1.00000000000000))*(cj7)*(x2342)*(x2343)))+(((cj3)*(r02)*(sj7))));
10536 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
10537 {
10538 continue;
10539 }
10540 }
10541 
10542 {
10543 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10544 vinfos[0].jointtype = 1;
10545 vinfos[0].foffset = j3;
10546 vinfos[0].indices[0] = _ij3[0];
10547 vinfos[0].indices[1] = _ij3[1];
10548 vinfos[0].maxsolutions = _nj3;
10549 vinfos[1].jointtype = 1;
10550 vinfos[1].foffset = j4;
10551 vinfos[1].indices[0] = _ij4[0];
10552 vinfos[1].indices[1] = _ij4[1];
10553 vinfos[1].maxsolutions = _nj4;
10554 vinfos[2].jointtype = 1;
10555 vinfos[2].foffset = j5;
10556 vinfos[2].indices[0] = _ij5[0];
10557 vinfos[2].indices[1] = _ij5[1];
10558 vinfos[2].maxsolutions = _nj5;
10559 vinfos[3].jointtype = 1;
10560 vinfos[3].foffset = j6;
10561 vinfos[3].indices[0] = _ij6[0];
10562 vinfos[3].indices[1] = _ij6[1];
10563 vinfos[3].maxsolutions = _nj6;
10564 vinfos[4].jointtype = 1;
10565 vinfos[4].foffset = j7;
10566 vinfos[4].indices[0] = _ij7[0];
10567 vinfos[4].indices[1] = _ij7[1];
10568 vinfos[4].maxsolutions = _nj7;
10569 vinfos[5].jointtype = 1;
10570 vinfos[5].foffset = j8;
10571 vinfos[5].indices[0] = _ij8[0];
10572 vinfos[5].indices[1] = _ij8[1];
10573 vinfos[5].maxsolutions = _nj8;
10574 std::vector<int> vfree(0);
10575 solutions.AddSolution(vinfos,vfree);
10576 }
10577 }
10578 }
10579 
10580 }
10581 
10582 }
10583 
10584 } else
10585 {
10586 {
10587 IkReal j4array[1], cj4array[1], sj4array[1];
10588 bool j4valid[1]={false};
10589 _nj4 = 1;
10590 IkReal x2350=((cj8)*(sj5));
10591 IkReal x2351=((sj5)*(sj8));
10592 IkReal x2352=((r22)*(sj7));
10593 IkReal x2353=((cj7)*(r20));
10594 IkReal x2354=((cj5)*(cj8));
10595 IkReal x2355=((cj7)*(r21));
10596 IkReal x2356=((cj5)*(sj8));
10597 if( IKabs(((gconst50)*(((((x2351)*(x2355)))+(((r20)*(x2356)))+(((IkReal(-1.00000000000000))*(sj5)*(x2352)))+(((r21)*(x2354)))+(((IkReal(-1.00000000000000))*(x2350)*(x2353))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(x2355)*(x2356)))+(((x2353)*(x2354)))+(((r20)*(x2351)))+(((r21)*(x2350)))+(((cj5)*(x2352))))))) < IKFAST_ATAN2_MAGTHRESH )
10598  continue;
10599 j4array[0]=IKatan2(((gconst50)*(((((x2351)*(x2355)))+(((r20)*(x2356)))+(((IkReal(-1.00000000000000))*(sj5)*(x2352)))+(((r21)*(x2354)))+(((IkReal(-1.00000000000000))*(x2350)*(x2353)))))), ((gconst50)*(((((IkReal(-1.00000000000000))*(x2355)*(x2356)))+(((x2353)*(x2354)))+(((r20)*(x2351)))+(((r21)*(x2350)))+(((cj5)*(x2352)))))));
10600 sj4array[0]=IKsin(j4array[0]);
10601 cj4array[0]=IKcos(j4array[0]);
10602 if( j4array[0] > IKPI )
10603 {
10604  j4array[0]-=IK2PI;
10605 }
10606 else if( j4array[0] < -IKPI )
10607 { j4array[0]+=IK2PI;
10608 }
10609 j4valid[0] = true;
10610 for(int ij4 = 0; ij4 < 1; ++ij4)
10611 {
10612 if( !j4valid[ij4] )
10613 {
10614  continue;
10615 }
10616 _ij4[0] = ij4; _ij4[1] = -1;
10617 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10618 {
10619 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10620 {
10621  j4valid[iij4]=false; _ij4[1] = iij4; break;
10622 }
10623 }
10624 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10625 {
10626 IkReal evalcond[4];
10627 IkReal x2357=IKsin(j4);
10628 IkReal x2358=IKcos(j4);
10629 IkReal x2359=((IkReal(1.00000000000000))*(cj8));
10630 IkReal x2360=((cj3)*(r01));
10631 IkReal x2361=((cj3)*(r00));
10632 IkReal x2362=((cj7)*(cj8));
10633 IkReal x2363=((r11)*(sj3));
10634 IkReal x2364=((IkReal(1.00000000000000))*(sj8));
10635 IkReal x2365=((r10)*(sj3));
10636 IkReal x2366=((sj5)*(x2358));
10637 IkReal x2367=((cj5)*(x2357));
10638 IkReal x2368=((cj5)*(x2358));
10639 IkReal x2369=((sj5)*(x2357));
10640 IkReal x2370=((x2367)+(x2366));
10641 evalcond[0]=((x2370)+(((cj8)*(r21)))+(((r20)*(sj8))));
10642 evalcond[1]=((x2369)+(((IkReal(-1.00000000000000))*(x2368)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2359)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
10643 evalcond[2]=((x2368)+(((IkReal(-1.00000000000000))*(x2369)))+(((IkReal(-1.00000000000000))*(x2359)*(x2363)))+(((IkReal(-1.00000000000000))*(x2359)*(x2360)))+(((IkReal(-1.00000000000000))*(x2364)*(x2365)))+(((IkReal(-1.00000000000000))*(x2361)*(x2364))));
10644 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2360)*(x2364)))+(x2370)+(((x2361)*(x2362)))+(((cj3)*(r02)*(sj7)))+(((x2362)*(x2365)))+(((IkReal(-1.00000000000000))*(cj7)*(x2363)*(x2364))));
10645 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
10646 {
10647 continue;
10648 }
10649 }
10650 
10651 {
10652 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10653 vinfos[0].jointtype = 1;
10654 vinfos[0].foffset = j3;
10655 vinfos[0].indices[0] = _ij3[0];
10656 vinfos[0].indices[1] = _ij3[1];
10657 vinfos[0].maxsolutions = _nj3;
10658 vinfos[1].jointtype = 1;
10659 vinfos[1].foffset = j4;
10660 vinfos[1].indices[0] = _ij4[0];
10661 vinfos[1].indices[1] = _ij4[1];
10662 vinfos[1].maxsolutions = _nj4;
10663 vinfos[2].jointtype = 1;
10664 vinfos[2].foffset = j5;
10665 vinfos[2].indices[0] = _ij5[0];
10666 vinfos[2].indices[1] = _ij5[1];
10667 vinfos[2].maxsolutions = _nj5;
10668 vinfos[3].jointtype = 1;
10669 vinfos[3].foffset = j6;
10670 vinfos[3].indices[0] = _ij6[0];
10671 vinfos[3].indices[1] = _ij6[1];
10672 vinfos[3].maxsolutions = _nj6;
10673 vinfos[4].jointtype = 1;
10674 vinfos[4].foffset = j7;
10675 vinfos[4].indices[0] = _ij7[0];
10676 vinfos[4].indices[1] = _ij7[1];
10677 vinfos[4].maxsolutions = _nj7;
10678 vinfos[5].jointtype = 1;
10679 vinfos[5].foffset = j8;
10680 vinfos[5].indices[0] = _ij8[0];
10681 vinfos[5].indices[1] = _ij8[1];
10682 vinfos[5].maxsolutions = _nj8;
10683 std::vector<int> vfree(0);
10684 solutions.AddSolution(vinfos,vfree);
10685 }
10686 }
10687 }
10688 
10689 }
10690 
10691 }
10692 
10693 } else
10694 {
10695 IkReal x2371=((cj3)*(cj8));
10696 IkReal x2372=((IkReal(1.00000000000000))*(sj7));
10697 IkReal x2373=((cj8)*(npx));
10698 IkReal x2374=((cj8)*(sj3));
10699 IkReal x2375=((npy)*(sj8));
10700 IkReal x2376=((r02)*(sj3));
10701 IkReal x2377=((IkReal(1.00000000000000))*(r11));
10702 IkReal x2378=((cj3)*(r12));
10703 IkReal x2379=((IkReal(1.00000000000000))*(cj7));
10704 IkReal x2380=((sj3)*(sj8));
10705 IkReal x2381=((IkReal(1.00000000000000))*(cj3)*(sj8));
10706 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
10707 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
10708 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
10709 evalcond[3]=((IkReal(0.235000000000000))+(((cj7)*(x2375)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x2372)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(x2373)*(x2379))));
10710 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x2381)))+(((r00)*(x2380)))+(((IkReal(-1.00000000000000))*(x2371)*(x2377)))+(((r01)*(x2374))));
10711 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x2375)))+(((IkReal(-1.00000000000000))*(x2372)*(x2373)))+(((cj7)*(npz)))+(((IkReal(-0.250000000000000))*(sj5))));
10712 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x2381)))+(((IkReal(-1.00000000000000))*(r10)*(x2380)))+(((IkReal(-1.00000000000000))*(x2374)*(x2377)))+(((IkReal(-1.00000000000000))*(r01)*(x2371))));
10713 evalcond[7]=((((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x2377)))+(((IkReal(-1.00000000000000))*(r00)*(x2374)*(x2379)))+(((cj7)*(r10)*(x2371)))+(((sj7)*(x2378)))+(((IkReal(-1.00000000000000))*(x2372)*(x2376)))+(((cj7)*(r01)*(x2380))));
10714 evalcond[8]=((((r10)*(sj7)*(x2371)))+(((cj7)*(x2376)))+(((r01)*(sj7)*(x2380)))+(((IkReal(-1.00000000000000))*(r00)*(x2372)*(x2374)))+(((IkReal(-1.00000000000000))*(x2378)*(x2379)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x2372))));
10715 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
10716 {
10717 {
10718 IkReal dummyeval[1];
10719 IkReal gconst52;
10720 gconst52=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
10721 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
10722 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10723 {
10724 {
10725 IkReal dummyeval[1];
10726 IkReal gconst53;
10727 gconst53=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
10728 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
10729 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10730 {
10731 continue;
10732 
10733 } else
10734 {
10735 {
10736 IkReal j4array[1], cj4array[1], sj4array[1];
10737 bool j4valid[1]={false};
10738 _nj4 = 1;
10739 IkReal x2382=((cj3)*(cj5));
10740 IkReal x2383=((r02)*(sj7));
10741 IkReal x2384=((cj5)*(sj7));
10742 IkReal x2385=((cj3)*(sj5));
10743 IkReal x2386=((r11)*(sj3));
10744 IkReal x2387=((r10)*(sj3));
10745 IkReal x2388=((r12)*(sj3));
10746 IkReal x2389=((sj5)*(sj7));
10747 IkReal x2390=((cj7)*(cj8)*(sj5));
10748 IkReal x2391=((IkReal(1.00000000000000))*(cj7)*(sj8));
10749 IkReal x2392=((cj5)*(cj7)*(cj8));
10750 if( IKabs(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(cj5)*(x2386)*(x2391)))+(((x2387)*(x2392)))+(((x2384)*(x2388)))+(((IkReal(-1.00000000000000))*(r22)*(x2389)))+(((x2382)*(x2383)))+(((IkReal(-1.00000000000000))*(r01)*(x2382)*(x2391)))+(((IkReal(-1.00000000000000))*(r20)*(x2390)))+(((cj7)*(cj8)*(r00)*(x2382))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((x2387)*(x2390)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2391)))+(((r20)*(x2392)))+(((x2383)*(x2385)))+(((r22)*(x2384)))+(((IkReal(-1.00000000000000))*(sj5)*(x2386)*(x2391)))+(((x2388)*(x2389)))+(((cj7)*(cj8)*(r00)*(x2385)))+(((IkReal(-1.00000000000000))*(r01)*(x2385)*(x2391))))))) < IKFAST_ATAN2_MAGTHRESH )
10751  continue;
10752 j4array[0]=IKatan2(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(cj5)*(x2386)*(x2391)))+(((x2387)*(x2392)))+(((x2384)*(x2388)))+(((IkReal(-1.00000000000000))*(r22)*(x2389)))+(((x2382)*(x2383)))+(((IkReal(-1.00000000000000))*(r01)*(x2382)*(x2391)))+(((IkReal(-1.00000000000000))*(r20)*(x2390)))+(((cj7)*(cj8)*(r00)*(x2382)))))), ((gconst53)*(((((x2387)*(x2390)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2391)))+(((r20)*(x2392)))+(((x2383)*(x2385)))+(((r22)*(x2384)))+(((IkReal(-1.00000000000000))*(sj5)*(x2386)*(x2391)))+(((x2388)*(x2389)))+(((cj7)*(cj8)*(r00)*(x2385)))+(((IkReal(-1.00000000000000))*(r01)*(x2385)*(x2391)))))));
10753 sj4array[0]=IKsin(j4array[0]);
10754 cj4array[0]=IKcos(j4array[0]);
10755 if( j4array[0] > IKPI )
10756 {
10757  j4array[0]-=IK2PI;
10758 }
10759 else if( j4array[0] < -IKPI )
10760 { j4array[0]+=IK2PI;
10761 }
10762 j4valid[0] = true;
10763 for(int ij4 = 0; ij4 < 1; ++ij4)
10764 {
10765 if( !j4valid[ij4] )
10766 {
10767  continue;
10768 }
10769 _ij4[0] = ij4; _ij4[1] = -1;
10770 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10771 {
10772 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10773 {
10774  j4valid[iij4]=false; _ij4[1] = iij4; break;
10775 }
10776 }
10777 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10778 {
10779 IkReal evalcond[4];
10780 IkReal x2393=IKcos(j4);
10781 IkReal x2394=IKsin(j4);
10782 IkReal x2395=((IkReal(1.00000000000000))*(cj7));
10783 IkReal x2396=((cj8)*(r20));
10784 IkReal x2397=((cj3)*(r02));
10785 IkReal x2398=((IkReal(1.00000000000000))*(sj7));
10786 IkReal x2399=((sj3)*(sj7));
10787 IkReal x2400=((r21)*(sj8));
10788 IkReal x2401=((cj8)*(r10));
10789 IkReal x2402=((sj5)*(x2393));
10790 IkReal x2403=((cj5)*(x2394));
10791 IkReal x2404=((r11)*(sj3)*(sj8));
10792 IkReal x2405=((cj3)*(cj8)*(r00));
10793 IkReal x2406=((cj5)*(x2393));
10794 IkReal x2407=((cj3)*(r01)*(sj8));
10795 IkReal x2408=((sj5)*(x2394));
10796 IkReal x2409=((x2402)+(x2403));
10797 evalcond[0]=((((IkReal(-1.00000000000000))*(x2406)))+(x2408)+(((cj7)*(x2400)))+(((IkReal(-1.00000000000000))*(r22)*(x2398)))+(((IkReal(-1.00000000000000))*(x2395)*(x2396))));
10798 evalcond[1]=((x2409)+(((IkReal(-1.00000000000000))*(x2396)*(x2398)))+(((sj7)*(x2400)))+(((cj7)*(r22))));
10799 evalcond[2]=((((r12)*(x2399)))+(x2409)+(((cj7)*(x2405)))+(((cj7)*(sj3)*(x2401)))+(((IkReal(-1.00000000000000))*(x2395)*(x2404)))+(((IkReal(-1.00000000000000))*(x2395)*(x2407)))+(((sj7)*(x2397))));
10800 evalcond[3]=((((IkReal(-1.00000000000000))*(x2408)))+(x2406)+(((x2399)*(x2401)))+(((sj7)*(x2405)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2395)))+(((IkReal(-1.00000000000000))*(x2395)*(x2397)))+(((IkReal(-1.00000000000000))*(x2398)*(x2407)))+(((IkReal(-1.00000000000000))*(x2398)*(x2404))));
10801 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
10802 {
10803 continue;
10804 }
10805 }
10806 
10807 {
10808 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10809 vinfos[0].jointtype = 1;
10810 vinfos[0].foffset = j3;
10811 vinfos[0].indices[0] = _ij3[0];
10812 vinfos[0].indices[1] = _ij3[1];
10813 vinfos[0].maxsolutions = _nj3;
10814 vinfos[1].jointtype = 1;
10815 vinfos[1].foffset = j4;
10816 vinfos[1].indices[0] = _ij4[0];
10817 vinfos[1].indices[1] = _ij4[1];
10818 vinfos[1].maxsolutions = _nj4;
10819 vinfos[2].jointtype = 1;
10820 vinfos[2].foffset = j5;
10821 vinfos[2].indices[0] = _ij5[0];
10822 vinfos[2].indices[1] = _ij5[1];
10823 vinfos[2].maxsolutions = _nj5;
10824 vinfos[3].jointtype = 1;
10825 vinfos[3].foffset = j6;
10826 vinfos[3].indices[0] = _ij6[0];
10827 vinfos[3].indices[1] = _ij6[1];
10828 vinfos[3].maxsolutions = _nj6;
10829 vinfos[4].jointtype = 1;
10830 vinfos[4].foffset = j7;
10831 vinfos[4].indices[0] = _ij7[0];
10832 vinfos[4].indices[1] = _ij7[1];
10833 vinfos[4].maxsolutions = _nj7;
10834 vinfos[5].jointtype = 1;
10835 vinfos[5].foffset = j8;
10836 vinfos[5].indices[0] = _ij8[0];
10837 vinfos[5].indices[1] = _ij8[1];
10838 vinfos[5].maxsolutions = _nj8;
10839 std::vector<int> vfree(0);
10840 solutions.AddSolution(vinfos,vfree);
10841 }
10842 }
10843 }
10844 
10845 }
10846 
10847 }
10848 
10849 } else
10850 {
10851 {
10852 IkReal j4array[1], cj4array[1], sj4array[1];
10853 bool j4valid[1]={false};
10854 _nj4 = 1;
10855 IkReal x2410=((r21)*(sj8));
10856 IkReal x2411=((sj5)*(sj7));
10857 IkReal x2412=((cj5)*(sj7));
10858 IkReal x2413=((cj5)*(cj7));
10859 IkReal x2414=((cj8)*(r20));
10860 IkReal x2415=((cj7)*(sj5));
10861 if( IKabs(((gconst52)*(((((r22)*(x2413)))+(((IkReal(-1.00000000000000))*(x2412)*(x2414)))+(((IkReal(-1.00000000000000))*(x2414)*(x2415)))+(((x2410)*(x2415)))+(((x2410)*(x2412)))+(((IkReal(-1.00000000000000))*(r22)*(x2411))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((r22)*(x2412)))+(((r22)*(x2415)))+(((x2413)*(x2414)))+(((x2410)*(x2411)))+(((IkReal(-1.00000000000000))*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(x2410)*(x2413))))))) < IKFAST_ATAN2_MAGTHRESH )
10862  continue;
10863 j4array[0]=IKatan2(((gconst52)*(((((r22)*(x2413)))+(((IkReal(-1.00000000000000))*(x2412)*(x2414)))+(((IkReal(-1.00000000000000))*(x2414)*(x2415)))+(((x2410)*(x2415)))+(((x2410)*(x2412)))+(((IkReal(-1.00000000000000))*(r22)*(x2411)))))), ((gconst52)*(((((r22)*(x2412)))+(((r22)*(x2415)))+(((x2413)*(x2414)))+(((x2410)*(x2411)))+(((IkReal(-1.00000000000000))*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(x2410)*(x2413)))))));
10864 sj4array[0]=IKsin(j4array[0]);
10865 cj4array[0]=IKcos(j4array[0]);
10866 if( j4array[0] > IKPI )
10867 {
10868  j4array[0]-=IK2PI;
10869 }
10870 else if( j4array[0] < -IKPI )
10871 { j4array[0]+=IK2PI;
10872 }
10873 j4valid[0] = true;
10874 for(int ij4 = 0; ij4 < 1; ++ij4)
10875 {
10876 if( !j4valid[ij4] )
10877 {
10878  continue;
10879 }
10880 _ij4[0] = ij4; _ij4[1] = -1;
10881 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10882 {
10883 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10884 {
10885  j4valid[iij4]=false; _ij4[1] = iij4; break;
10886 }
10887 }
10888 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10889 {
10890 IkReal evalcond[4];
10891 IkReal x2416=IKcos(j4);
10892 IkReal x2417=IKsin(j4);
10893 IkReal x2418=((IkReal(1.00000000000000))*(cj7));
10894 IkReal x2419=((cj8)*(r20));
10895 IkReal x2420=((cj3)*(r02));
10896 IkReal x2421=((IkReal(1.00000000000000))*(sj7));
10897 IkReal x2422=((sj3)*(sj7));
10898 IkReal x2423=((r21)*(sj8));
10899 IkReal x2424=((cj8)*(r10));
10900 IkReal x2425=((sj5)*(x2416));
10901 IkReal x2426=((cj5)*(x2417));
10902 IkReal x2427=((r11)*(sj3)*(sj8));
10903 IkReal x2428=((cj3)*(cj8)*(r00));
10904 IkReal x2429=((cj5)*(x2416));
10905 IkReal x2430=((cj3)*(r01)*(sj8));
10906 IkReal x2431=((sj5)*(x2417));
10907 IkReal x2432=((x2425)+(x2426));
10908 evalcond[0]=((x2431)+(((IkReal(-1.00000000000000))*(r22)*(x2421)))+(((IkReal(-1.00000000000000))*(x2429)))+(((cj7)*(x2423)))+(((IkReal(-1.00000000000000))*(x2418)*(x2419))));
10909 evalcond[1]=((x2432)+(((IkReal(-1.00000000000000))*(x2419)*(x2421)))+(((cj7)*(r22)))+(((sj7)*(x2423))));
10910 evalcond[2]=((x2432)+(((IkReal(-1.00000000000000))*(x2418)*(x2430)))+(((IkReal(-1.00000000000000))*(x2418)*(x2427)))+(((cj7)*(x2428)))+(((r12)*(x2422)))+(((cj7)*(sj3)*(x2424)))+(((sj7)*(x2420))));
10911 evalcond[3]=((((IkReal(-1.00000000000000))*(x2431)))+(x2429)+(((IkReal(-1.00000000000000))*(x2421)*(x2430)))+(((x2422)*(x2424)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2418)))+(((IkReal(-1.00000000000000))*(x2421)*(x2427)))+(((IkReal(-1.00000000000000))*(x2418)*(x2420)))+(((sj7)*(x2428))));
10912 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
10913 {
10914 continue;
10915 }
10916 }
10917 
10918 {
10919 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10920 vinfos[0].jointtype = 1;
10921 vinfos[0].foffset = j3;
10922 vinfos[0].indices[0] = _ij3[0];
10923 vinfos[0].indices[1] = _ij3[1];
10924 vinfos[0].maxsolutions = _nj3;
10925 vinfos[1].jointtype = 1;
10926 vinfos[1].foffset = j4;
10927 vinfos[1].indices[0] = _ij4[0];
10928 vinfos[1].indices[1] = _ij4[1];
10929 vinfos[1].maxsolutions = _nj4;
10930 vinfos[2].jointtype = 1;
10931 vinfos[2].foffset = j5;
10932 vinfos[2].indices[0] = _ij5[0];
10933 vinfos[2].indices[1] = _ij5[1];
10934 vinfos[2].maxsolutions = _nj5;
10935 vinfos[3].jointtype = 1;
10936 vinfos[3].foffset = j6;
10937 vinfos[3].indices[0] = _ij6[0];
10938 vinfos[3].indices[1] = _ij6[1];
10939 vinfos[3].maxsolutions = _nj6;
10940 vinfos[4].jointtype = 1;
10941 vinfos[4].foffset = j7;
10942 vinfos[4].indices[0] = _ij7[0];
10943 vinfos[4].indices[1] = _ij7[1];
10944 vinfos[4].maxsolutions = _nj7;
10945 vinfos[5].jointtype = 1;
10946 vinfos[5].foffset = j8;
10947 vinfos[5].indices[0] = _ij8[0];
10948 vinfos[5].indices[1] = _ij8[1];
10949 vinfos[5].maxsolutions = _nj8;
10950 std::vector<int> vfree(0);
10951 solutions.AddSolution(vinfos,vfree);
10952 }
10953 }
10954 }
10955 
10956 }
10957 
10958 }
10959 
10960 } else
10961 {
10962 IkReal x2433=((cj3)*(cj8));
10963 IkReal x2434=((IkReal(1.00000000000000))*(sj7));
10964 IkReal x2435=((cj8)*(npx));
10965 IkReal x2436=((cj8)*(sj3));
10966 IkReal x2437=((npy)*(sj8));
10967 IkReal x2438=((r02)*(sj3));
10968 IkReal x2439=((IkReal(1.00000000000000))*(r11));
10969 IkReal x2440=((cj3)*(r12));
10970 IkReal x2441=((IkReal(1.00000000000000))*(cj7));
10971 IkReal x2442=((sj3)*(sj8));
10972 IkReal x2443=((IkReal(1.00000000000000))*(cj3)*(sj8));
10973 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
10974 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
10975 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
10976 evalcond[3]=((IkReal(0.235000000000000))+(((cj7)*(x2437)))+(((IkReal(-1.00000000000000))*(npz)*(x2434)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(x2435)*(x2441)))+(((IkReal(0.250000000000000))*(cj5))));
10977 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2433)*(x2439)))+(((r01)*(x2436)))+(((IkReal(-1.00000000000000))*(r10)*(x2443)))+(((r00)*(x2442))));
10978 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(0.250000000000000))*(sj5)))+(((IkReal(-1.00000000000000))*(x2434)*(x2435)))+(((sj7)*(x2437)))+(((cj7)*(npz))));
10979 evalcond[6]=((((IkReal(-1.00000000000000))*(r10)*(x2442)))+(((IkReal(-1.00000000000000))*(r01)*(x2433)))+(((IkReal(-1.00000000000000))*(x2436)*(x2439)))+(((IkReal(-1.00000000000000))*(r00)*(x2443))));
10980 evalcond[7]=((((sj7)*(x2440)))+(((cj7)*(r01)*(x2442)))+(((IkReal(-1.00000000000000))*(r00)*(x2436)*(x2441)))+(((IkReal(-1.00000000000000))*(x2434)*(x2438)))+(((cj7)*(r10)*(x2433)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x2439))));
10981 evalcond[8]=((((cj7)*(x2438)))+(((IkReal(-1.00000000000000))*(r00)*(x2434)*(x2436)))+(((r10)*(sj7)*(x2433)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x2434)))+(((r01)*(sj7)*(x2442)))+(((IkReal(-1.00000000000000))*(x2440)*(x2441))));
10982 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
10983 {
10984 {
10985 IkReal dummyeval[1];
10986 IkReal gconst54;
10987 gconst54=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
10988 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
10989 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10990 {
10991 {
10992 IkReal dummyeval[1];
10993 IkReal gconst55;
10994 gconst55=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
10995 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
10996 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
10997 {
10998 continue;
10999 
11000 } else
11001 {
11002 {
11003 IkReal j4array[1], cj4array[1], sj4array[1];
11004 bool j4valid[1]={false};
11005 _nj4 = 1;
11006 IkReal x2444=((cj3)*(cj5));
11007 IkReal x2445=((r02)*(sj7));
11008 IkReal x2446=((cj8)*(r00));
11009 IkReal x2447=((cj5)*(sj7));
11010 IkReal x2448=((cj5)*(sj3));
11011 IkReal x2449=((sj3)*(sj5));
11012 IkReal x2450=((IkReal(1.00000000000000))*(sj5));
11013 IkReal x2451=((cj3)*(cj7)*(sj5));
11014 IkReal x2452=((IkReal(1.00000000000000))*(cj7)*(sj8));
11015 IkReal x2453=((cj7)*(cj8)*(r10));
11016 IkReal x2454=((cj7)*(cj8)*(r20));
11017 if( IKabs(((gconst55)*(((((IkReal(-1.00000000000000))*(x2450)*(x2454)))+(((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r11)*(x2448)*(x2452)))+(((IkReal(-1.00000000000000))*(r01)*(x2444)*(x2452)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2450)))+(((x2448)*(x2453)))+(((r12)*(sj3)*(x2447)))+(((x2444)*(x2445)))+(((cj7)*(x2444)*(x2446))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((cj3)*(sj5)*(x2445)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2450)))+(((r22)*(x2447)))+(((x2449)*(x2453)))+(((cj5)*(x2454)))+(((r12)*(sj7)*(x2449)))+(((IkReal(-1.00000000000000))*(r11)*(x2449)*(x2452)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2452)))+(((x2446)*(x2451))))))) < IKFAST_ATAN2_MAGTHRESH )
11018  continue;
11019 j4array[0]=IKatan2(((gconst55)*(((((IkReal(-1.00000000000000))*(x2450)*(x2454)))+(((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r11)*(x2448)*(x2452)))+(((IkReal(-1.00000000000000))*(r01)*(x2444)*(x2452)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2450)))+(((x2448)*(x2453)))+(((r12)*(sj3)*(x2447)))+(((x2444)*(x2445)))+(((cj7)*(x2444)*(x2446)))))), ((gconst55)*(((((cj3)*(sj5)*(x2445)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2450)))+(((r22)*(x2447)))+(((x2449)*(x2453)))+(((cj5)*(x2454)))+(((r12)*(sj7)*(x2449)))+(((IkReal(-1.00000000000000))*(r11)*(x2449)*(x2452)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2452)))+(((x2446)*(x2451)))))));
11020 sj4array[0]=IKsin(j4array[0]);
11021 cj4array[0]=IKcos(j4array[0]);
11022 if( j4array[0] > IKPI )
11023 {
11024  j4array[0]-=IK2PI;
11025 }
11026 else if( j4array[0] < -IKPI )
11027 { j4array[0]+=IK2PI;
11028 }
11029 j4valid[0] = true;
11030 for(int ij4 = 0; ij4 < 1; ++ij4)
11031 {
11032 if( !j4valid[ij4] )
11033 {
11034  continue;
11035 }
11036 _ij4[0] = ij4; _ij4[1] = -1;
11037 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11038 {
11039 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11040 {
11041  j4valid[iij4]=false; _ij4[1] = iij4; break;
11042 }
11043 }
11044 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11045 {
11046 IkReal evalcond[4];
11047 IkReal x2455=IKcos(j4);
11048 IkReal x2456=IKsin(j4);
11049 IkReal x2457=((IkReal(1.00000000000000))*(cj7));
11050 IkReal x2458=((cj8)*(r20));
11051 IkReal x2459=((cj3)*(r02));
11052 IkReal x2460=((IkReal(1.00000000000000))*(sj7));
11053 IkReal x2461=((sj3)*(sj7));
11054 IkReal x2462=((r21)*(sj8));
11055 IkReal x2463=((IkReal(1.00000000000000))*(cj5));
11056 IkReal x2464=((cj8)*(r10));
11057 IkReal x2465=((sj5)*(x2456));
11058 IkReal x2466=((sj5)*(x2455));
11059 IkReal x2467=((r11)*(sj3)*(sj8));
11060 IkReal x2468=((cj3)*(cj8)*(r00));
11061 IkReal x2469=((cj3)*(r01)*(sj8));
11062 IkReal x2470=((x2455)*(x2463));
11063 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x2460)))+(x2465)+(((IkReal(-1.00000000000000))*(x2470)))+(((IkReal(-1.00000000000000))*(x2457)*(x2458)))+(((cj7)*(x2462))));
11064 evalcond[1]=((((IkReal(-1.00000000000000))*(x2456)*(x2463)))+(((IkReal(-1.00000000000000))*(x2466)))+(((sj7)*(x2462)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x2458)*(x2460))));
11065 evalcond[2]=((x2466)+(((sj7)*(x2459)))+(((IkReal(-1.00000000000000))*(x2457)*(x2467)))+(((IkReal(-1.00000000000000))*(x2457)*(x2469)))+(((r12)*(x2461)))+(((cj5)*(x2456)))+(((cj7)*(sj3)*(x2464)))+(((cj7)*(x2468))));
11066 evalcond[3]=((x2465)+(((x2461)*(x2464)))+(((sj7)*(x2468)))+(((IkReal(-1.00000000000000))*(x2470)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2457)))+(((IkReal(-1.00000000000000))*(x2457)*(x2459)))+(((IkReal(-1.00000000000000))*(x2460)*(x2467)))+(((IkReal(-1.00000000000000))*(x2460)*(x2469))));
11067 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
11068 {
11069 continue;
11070 }
11071 }
11072 
11073 {
11074 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11075 vinfos[0].jointtype = 1;
11076 vinfos[0].foffset = j3;
11077 vinfos[0].indices[0] = _ij3[0];
11078 vinfos[0].indices[1] = _ij3[1];
11079 vinfos[0].maxsolutions = _nj3;
11080 vinfos[1].jointtype = 1;
11081 vinfos[1].foffset = j4;
11082 vinfos[1].indices[0] = _ij4[0];
11083 vinfos[1].indices[1] = _ij4[1];
11084 vinfos[1].maxsolutions = _nj4;
11085 vinfos[2].jointtype = 1;
11086 vinfos[2].foffset = j5;
11087 vinfos[2].indices[0] = _ij5[0];
11088 vinfos[2].indices[1] = _ij5[1];
11089 vinfos[2].maxsolutions = _nj5;
11090 vinfos[3].jointtype = 1;
11091 vinfos[3].foffset = j6;
11092 vinfos[3].indices[0] = _ij6[0];
11093 vinfos[3].indices[1] = _ij6[1];
11094 vinfos[3].maxsolutions = _nj6;
11095 vinfos[4].jointtype = 1;
11096 vinfos[4].foffset = j7;
11097 vinfos[4].indices[0] = _ij7[0];
11098 vinfos[4].indices[1] = _ij7[1];
11099 vinfos[4].maxsolutions = _nj7;
11100 vinfos[5].jointtype = 1;
11101 vinfos[5].foffset = j8;
11102 vinfos[5].indices[0] = _ij8[0];
11103 vinfos[5].indices[1] = _ij8[1];
11104 vinfos[5].maxsolutions = _nj8;
11105 std::vector<int> vfree(0);
11106 solutions.AddSolution(vinfos,vfree);
11107 }
11108 }
11109 }
11110 
11111 }
11112 
11113 }
11114 
11115 } else
11116 {
11117 {
11118 IkReal j4array[1], cj4array[1], sj4array[1];
11119 bool j4valid[1]={false};
11120 _nj4 = 1;
11121 IkReal x2471=((cj7)*(sj5));
11122 IkReal x2472=((r21)*(sj8));
11123 IkReal x2473=((cj5)*(cj7));
11124 IkReal x2474=((cj8)*(r20));
11125 IkReal x2475=((IkReal(1.00000000000000))*(sj7));
11126 IkReal x2476=((sj5)*(sj7));
11127 if( IKabs(((gconst54)*(((((x2471)*(x2474)))+(((IkReal(-1.00000000000000))*(cj5)*(x2474)*(x2475)))+(((IkReal(-1.00000000000000))*(x2471)*(x2472)))+(((cj5)*(sj7)*(x2472)))+(((r22)*(x2476)))+(((r22)*(x2473))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)*(x2475)))+(((IkReal(-1.00000000000000))*(sj5)*(x2474)*(x2475)))+(((IkReal(-1.00000000000000))*(x2473)*(x2474)))+(((x2472)*(x2473)))+(((x2472)*(x2476)))+(((r22)*(x2471))))))) < IKFAST_ATAN2_MAGTHRESH )
11128  continue;
11129 j4array[0]=IKatan2(((gconst54)*(((((x2471)*(x2474)))+(((IkReal(-1.00000000000000))*(cj5)*(x2474)*(x2475)))+(((IkReal(-1.00000000000000))*(x2471)*(x2472)))+(((cj5)*(sj7)*(x2472)))+(((r22)*(x2476)))+(((r22)*(x2473)))))), ((gconst54)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)*(x2475)))+(((IkReal(-1.00000000000000))*(sj5)*(x2474)*(x2475)))+(((IkReal(-1.00000000000000))*(x2473)*(x2474)))+(((x2472)*(x2473)))+(((x2472)*(x2476)))+(((r22)*(x2471)))))));
11130 sj4array[0]=IKsin(j4array[0]);
11131 cj4array[0]=IKcos(j4array[0]);
11132 if( j4array[0] > IKPI )
11133 {
11134  j4array[0]-=IK2PI;
11135 }
11136 else if( j4array[0] < -IKPI )
11137 { j4array[0]+=IK2PI;
11138 }
11139 j4valid[0] = true;
11140 for(int ij4 = 0; ij4 < 1; ++ij4)
11141 {
11142 if( !j4valid[ij4] )
11143 {
11144  continue;
11145 }
11146 _ij4[0] = ij4; _ij4[1] = -1;
11147 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11148 {
11149 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11150 {
11151  j4valid[iij4]=false; _ij4[1] = iij4; break;
11152 }
11153 }
11154 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11155 {
11156 IkReal evalcond[4];
11157 IkReal x2477=IKcos(j4);
11158 IkReal x2478=IKsin(j4);
11159 IkReal x2479=((IkReal(1.00000000000000))*(cj7));
11160 IkReal x2480=((cj8)*(r20));
11161 IkReal x2481=((cj3)*(r02));
11162 IkReal x2482=((IkReal(1.00000000000000))*(sj7));
11163 IkReal x2483=((sj3)*(sj7));
11164 IkReal x2484=((r21)*(sj8));
11165 IkReal x2485=((IkReal(1.00000000000000))*(cj5));
11166 IkReal x2486=((cj8)*(r10));
11167 IkReal x2487=((sj5)*(x2478));
11168 IkReal x2488=((sj5)*(x2477));
11169 IkReal x2489=((r11)*(sj3)*(sj8));
11170 IkReal x2490=((cj3)*(cj8)*(r00));
11171 IkReal x2491=((cj3)*(r01)*(sj8));
11172 IkReal x2492=((x2477)*(x2485));
11173 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x2482)))+(x2487)+(((IkReal(-1.00000000000000))*(x2492)))+(((cj7)*(x2484)))+(((IkReal(-1.00000000000000))*(x2479)*(x2480))));
11174 evalcond[1]=((((IkReal(-1.00000000000000))*(x2488)))+(((sj7)*(x2484)))+(((IkReal(-1.00000000000000))*(x2480)*(x2482)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x2478)*(x2485))));
11175 evalcond[2]=((x2488)+(((cj5)*(x2478)))+(((sj7)*(x2481)))+(((cj7)*(x2490)))+(((r12)*(x2483)))+(((cj7)*(sj3)*(x2486)))+(((IkReal(-1.00000000000000))*(x2479)*(x2489)))+(((IkReal(-1.00000000000000))*(x2479)*(x2491))));
11176 evalcond[3]=((x2487)+(((x2483)*(x2486)))+(((IkReal(-1.00000000000000))*(x2492)))+(((IkReal(-1.00000000000000))*(x2482)*(x2491)))+(((sj7)*(x2490)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2479)))+(((IkReal(-1.00000000000000))*(x2482)*(x2489)))+(((IkReal(-1.00000000000000))*(x2479)*(x2481))));
11177 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
11178 {
11179 continue;
11180 }
11181 }
11182 
11183 {
11184 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11185 vinfos[0].jointtype = 1;
11186 vinfos[0].foffset = j3;
11187 vinfos[0].indices[0] = _ij3[0];
11188 vinfos[0].indices[1] = _ij3[1];
11189 vinfos[0].maxsolutions = _nj3;
11190 vinfos[1].jointtype = 1;
11191 vinfos[1].foffset = j4;
11192 vinfos[1].indices[0] = _ij4[0];
11193 vinfos[1].indices[1] = _ij4[1];
11194 vinfos[1].maxsolutions = _nj4;
11195 vinfos[2].jointtype = 1;
11196 vinfos[2].foffset = j5;
11197 vinfos[2].indices[0] = _ij5[0];
11198 vinfos[2].indices[1] = _ij5[1];
11199 vinfos[2].maxsolutions = _nj5;
11200 vinfos[3].jointtype = 1;
11201 vinfos[3].foffset = j6;
11202 vinfos[3].indices[0] = _ij6[0];
11203 vinfos[3].indices[1] = _ij6[1];
11204 vinfos[3].maxsolutions = _nj6;
11205 vinfos[4].jointtype = 1;
11206 vinfos[4].foffset = j7;
11207 vinfos[4].indices[0] = _ij7[0];
11208 vinfos[4].indices[1] = _ij7[1];
11209 vinfos[4].maxsolutions = _nj7;
11210 vinfos[5].jointtype = 1;
11211 vinfos[5].foffset = j8;
11212 vinfos[5].indices[0] = _ij8[0];
11213 vinfos[5].indices[1] = _ij8[1];
11214 vinfos[5].maxsolutions = _nj8;
11215 std::vector<int> vfree(0);
11216 solutions.AddSolution(vinfos,vfree);
11217 }
11218 }
11219 }
11220 
11221 }
11222 
11223 }
11224 
11225 } else
11226 {
11227 if( 1 )
11228 {
11229 continue;
11230 
11231 } else
11232 {
11233 }
11234 }
11235 }
11236 }
11237 }
11238 }
11239 
11240 } else
11241 {
11242 {
11243 IkReal j4array[1], cj4array[1], sj4array[1];
11244 bool j4valid[1]={false};
11245 _nj4 = 1;
11246 IkReal x2493=((r21)*(sj8));
11247 IkReal x2494=((IkReal(1.00000000000000))*(r22));
11248 IkReal x2495=((cj5)*(sj7));
11249 IkReal x2496=((cj6)*(cj7));
11250 IkReal x2497=((sj5)*(sj7));
11251 IkReal x2498=((cj5)*(cj8)*(r20));
11252 IkReal x2499=((IkReal(1.00000000000000))*(x2496));
11253 IkReal x2500=((cj8)*(r20)*(sj5));
11254 if( IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x2493)*(x2495)))+(((x2496)*(x2500)))+(((IkReal(-1.00000000000000))*(sj5)*(x2493)*(x2499)))+(((cj6)*(r22)*(x2497)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x2494)))+(((cj8)*(r20)*(x2495))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x2493)*(x2497)))+(((IkReal(-1.00000000000000))*(cj6)*(x2494)*(x2495)))+(((cj8)*(r20)*(x2497)))+(((IkReal(-1.00000000000000))*(x2498)*(x2499)))+(((cj5)*(x2493)*(x2496)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x2494))))))) < IKFAST_ATAN2_MAGTHRESH )
11255  continue;
11256 j4array[0]=IKatan2(((gconst47)*(((((IkReal(-1.00000000000000))*(x2493)*(x2495)))+(((x2496)*(x2500)))+(((IkReal(-1.00000000000000))*(sj5)*(x2493)*(x2499)))+(((cj6)*(r22)*(x2497)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x2494)))+(((cj8)*(r20)*(x2495)))))), ((gconst47)*(((((IkReal(-1.00000000000000))*(x2493)*(x2497)))+(((IkReal(-1.00000000000000))*(cj6)*(x2494)*(x2495)))+(((cj8)*(r20)*(x2497)))+(((IkReal(-1.00000000000000))*(x2498)*(x2499)))+(((cj5)*(x2493)*(x2496)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x2494)))))));
11257 sj4array[0]=IKsin(j4array[0]);
11258 cj4array[0]=IKcos(j4array[0]);
11259 if( j4array[0] > IKPI )
11260 {
11261  j4array[0]-=IK2PI;
11262 }
11263 else if( j4array[0] < -IKPI )
11264 { j4array[0]+=IK2PI;
11265 }
11266 j4valid[0] = true;
11267 for(int ij4 = 0; ij4 < 1; ++ij4)
11268 {
11269 if( !j4valid[ij4] )
11270 {
11271  continue;
11272 }
11273 _ij4[0] = ij4; _ij4[1] = -1;
11274 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11275 {
11276 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11277 {
11278  j4valid[iij4]=false; _ij4[1] = iij4; break;
11279 }
11280 }
11281 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11282 {
11283 IkReal evalcond[6];
11284 IkReal x2501=IKsin(j4);
11285 IkReal x2502=IKcos(j4);
11286 IkReal x2503=((IkReal(1.00000000000000))*(cj8));
11287 IkReal x2504=((cj3)*(r01));
11288 IkReal x2505=((IkReal(1.00000000000000))*(sj8));
11289 IkReal x2506=((r11)*(sj3));
11290 IkReal x2507=((cj3)*(r00));
11291 IkReal x2508=((IkReal(1.00000000000000))*(sj6));
11292 IkReal x2509=((IkReal(1.00000000000000))*(cj7));
11293 IkReal x2510=((cj3)*(r02));
11294 IkReal x2511=((sj3)*(sj7));
11295 IkReal x2512=((cj7)*(cj8));
11296 IkReal x2513=((r21)*(sj8));
11297 IkReal x2514=((r10)*(sj3));
11298 IkReal x2515=((sj5)*(x2502));
11299 IkReal x2516=((cj5)*(x2502));
11300 IkReal x2517=((cj6)*(x2501));
11301 IkReal x2518=((cj5)*(x2501));
11302 IkReal x2519=((sj5)*(x2501));
11303 evalcond[0]=((((IkReal(-1.00000000000000))*(x2508)*(x2515)))+(((IkReal(-1.00000000000000))*(x2508)*(x2518)))+(((cj8)*(r21)))+(((r20)*(sj8))));
11304 evalcond[1]=((x2519)+(((cj7)*(x2513)))+(((IkReal(-1.00000000000000))*(x2516)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2503))));
11305 evalcond[2]=((((cj5)*(x2517)))+(((sj7)*(x2513)))+(((IkReal(-1.00000000000000))*(r20)*(sj7)*(x2503)))+(((cj6)*(x2515)))+(((cj7)*(r22))));
11306 evalcond[3]=((((IkReal(-1.00000000000000))*(x2508)*(x2516)))+(((sj6)*(x2519)))+(((IkReal(-1.00000000000000))*(x2503)*(x2506)))+(((IkReal(-1.00000000000000))*(x2503)*(x2504)))+(((IkReal(-1.00000000000000))*(x2505)*(x2514)))+(((IkReal(-1.00000000000000))*(x2505)*(x2507))));
11307 evalcond[4]=((x2518)+(x2515)+(((x2512)*(x2514)))+(((sj7)*(x2510)))+(((IkReal(-1.00000000000000))*(cj7)*(x2504)*(x2505)))+(((x2507)*(x2512)))+(((IkReal(-1.00000000000000))*(cj7)*(x2505)*(x2506)))+(((r12)*(x2511))));
11308 evalcond[5]=((((cj8)*(r10)*(x2511)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2509)))+(((IkReal(-1.00000000000000))*(sj7)*(x2505)*(x2506)))+(((IkReal(-1.00000000000000))*(sj7)*(x2504)*(x2505)))+(((cj8)*(sj7)*(x2507)))+(((IkReal(-1.00000000000000))*(x2509)*(x2510)))+(((IkReal(-1.00000000000000))*(sj5)*(x2517)))+(((cj6)*(x2516))));
11309 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
11310 {
11311 continue;
11312 }
11313 }
11314 
11315 {
11316 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11317 vinfos[0].jointtype = 1;
11318 vinfos[0].foffset = j3;
11319 vinfos[0].indices[0] = _ij3[0];
11320 vinfos[0].indices[1] = _ij3[1];
11321 vinfos[0].maxsolutions = _nj3;
11322 vinfos[1].jointtype = 1;
11323 vinfos[1].foffset = j4;
11324 vinfos[1].indices[0] = _ij4[0];
11325 vinfos[1].indices[1] = _ij4[1];
11326 vinfos[1].maxsolutions = _nj4;
11327 vinfos[2].jointtype = 1;
11328 vinfos[2].foffset = j5;
11329 vinfos[2].indices[0] = _ij5[0];
11330 vinfos[2].indices[1] = _ij5[1];
11331 vinfos[2].maxsolutions = _nj5;
11332 vinfos[3].jointtype = 1;
11333 vinfos[3].foffset = j6;
11334 vinfos[3].indices[0] = _ij6[0];
11335 vinfos[3].indices[1] = _ij6[1];
11336 vinfos[3].maxsolutions = _nj6;
11337 vinfos[4].jointtype = 1;
11338 vinfos[4].foffset = j7;
11339 vinfos[4].indices[0] = _ij7[0];
11340 vinfos[4].indices[1] = _ij7[1];
11341 vinfos[4].maxsolutions = _nj7;
11342 vinfos[5].jointtype = 1;
11343 vinfos[5].foffset = j8;
11344 vinfos[5].indices[0] = _ij8[0];
11345 vinfos[5].indices[1] = _ij8[1];
11346 vinfos[5].maxsolutions = _nj8;
11347 std::vector<int> vfree(0);
11348 solutions.AddSolution(vinfos,vfree);
11349 }
11350 }
11351 }
11352 
11353 }
11354 
11355 }
11356 
11357 } else
11358 {
11359 {
11360 IkReal j4array[1], cj4array[1], sj4array[1];
11361 bool j4valid[1]={false};
11362 _nj4 = 1;
11363 IkReal x2520=((sj5)*(sj6));
11364 IkReal x2521=((r22)*(sj7));
11365 IkReal x2522=((r20)*(sj8));
11366 IkReal x2523=((cj8)*(r21));
11367 IkReal x2524=((cj5)*(sj6));
11368 IkReal x2525=((cj7)*(cj8)*(r20));
11369 IkReal x2526=((cj7)*(r21)*(sj8));
11370 if( IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(x2520)*(x2526)))+(((cj5)*(x2523)))+(((cj5)*(x2522)))+(((x2520)*(x2525)))+(((x2520)*(x2521))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((sj5)*(x2523)))+(((sj5)*(x2522)))+(((IkReal(-1.00000000000000))*(x2524)*(x2525)))+(((IkReal(-1.00000000000000))*(x2521)*(x2524)))+(((x2524)*(x2526))))))) < IKFAST_ATAN2_MAGTHRESH )
11371  continue;
11372 j4array[0]=IKatan2(((gconst46)*(((((IkReal(-1.00000000000000))*(x2520)*(x2526)))+(((cj5)*(x2523)))+(((cj5)*(x2522)))+(((x2520)*(x2525)))+(((x2520)*(x2521)))))), ((gconst46)*(((((sj5)*(x2523)))+(((sj5)*(x2522)))+(((IkReal(-1.00000000000000))*(x2524)*(x2525)))+(((IkReal(-1.00000000000000))*(x2521)*(x2524)))+(((x2524)*(x2526)))))));
11373 sj4array[0]=IKsin(j4array[0]);
11374 cj4array[0]=IKcos(j4array[0]);
11375 if( j4array[0] > IKPI )
11376 {
11377  j4array[0]-=IK2PI;
11378 }
11379 else if( j4array[0] < -IKPI )
11380 { j4array[0]+=IK2PI;
11381 }
11382 j4valid[0] = true;
11383 for(int ij4 = 0; ij4 < 1; ++ij4)
11384 {
11385 if( !j4valid[ij4] )
11386 {
11387  continue;
11388 }
11389 _ij4[0] = ij4; _ij4[1] = -1;
11390 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11391 {
11392 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11393 {
11394  j4valid[iij4]=false; _ij4[1] = iij4; break;
11395 }
11396 }
11397 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11398 {
11399 IkReal evalcond[6];
11400 IkReal x2527=IKsin(j4);
11401 IkReal x2528=IKcos(j4);
11402 IkReal x2529=((IkReal(1.00000000000000))*(cj8));
11403 IkReal x2530=((cj3)*(r01));
11404 IkReal x2531=((IkReal(1.00000000000000))*(sj8));
11405 IkReal x2532=((r11)*(sj3));
11406 IkReal x2533=((cj3)*(r00));
11407 IkReal x2534=((IkReal(1.00000000000000))*(sj6));
11408 IkReal x2535=((IkReal(1.00000000000000))*(cj7));
11409 IkReal x2536=((cj3)*(r02));
11410 IkReal x2537=((sj3)*(sj7));
11411 IkReal x2538=((cj7)*(cj8));
11412 IkReal x2539=((r21)*(sj8));
11413 IkReal x2540=((r10)*(sj3));
11414 IkReal x2541=((sj5)*(x2528));
11415 IkReal x2542=((cj5)*(x2528));
11416 IkReal x2543=((cj6)*(x2527));
11417 IkReal x2544=((cj5)*(x2527));
11418 IkReal x2545=((sj5)*(x2527));
11419 evalcond[0]=((((cj8)*(r21)))+(((r20)*(sj8)))+(((IkReal(-1.00000000000000))*(x2534)*(x2541)))+(((IkReal(-1.00000000000000))*(x2534)*(x2544))));
11420 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2529)))+(x2545)+(((cj7)*(x2539)))+(((IkReal(-1.00000000000000))*(x2542)))+(((IkReal(-1.00000000000000))*(r22)*(sj7))));
11421 evalcond[2]=((((IkReal(-1.00000000000000))*(r20)*(sj7)*(x2529)))+(((cj6)*(x2541)))+(((cj5)*(x2543)))+(((cj7)*(r22)))+(((sj7)*(x2539))));
11422 evalcond[3]=((((IkReal(-1.00000000000000))*(x2531)*(x2540)))+(((sj6)*(x2545)))+(((IkReal(-1.00000000000000))*(x2531)*(x2533)))+(((IkReal(-1.00000000000000))*(x2529)*(x2532)))+(((IkReal(-1.00000000000000))*(x2529)*(x2530)))+(((IkReal(-1.00000000000000))*(x2534)*(x2542))));
11423 evalcond[4]=((x2541)+(x2544)+(((IkReal(-1.00000000000000))*(cj7)*(x2530)*(x2531)))+(((x2538)*(x2540)))+(((x2533)*(x2538)))+(((r12)*(x2537)))+(((IkReal(-1.00000000000000))*(cj7)*(x2531)*(x2532)))+(((sj7)*(x2536))));
11424 evalcond[5]=((((cj6)*(x2542)))+(((cj8)*(sj7)*(x2533)))+(((IkReal(-1.00000000000000))*(x2535)*(x2536)))+(((IkReal(-1.00000000000000))*(sj7)*(x2531)*(x2532)))+(((IkReal(-1.00000000000000))*(sj5)*(x2543)))+(((IkReal(-1.00000000000000))*(sj7)*(x2530)*(x2531)))+(((cj8)*(r10)*(x2537)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2535))));
11425 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
11426 {
11427 continue;
11428 }
11429 }
11430 
11431 {
11432 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11433 vinfos[0].jointtype = 1;
11434 vinfos[0].foffset = j3;
11435 vinfos[0].indices[0] = _ij3[0];
11436 vinfos[0].indices[1] = _ij3[1];
11437 vinfos[0].maxsolutions = _nj3;
11438 vinfos[1].jointtype = 1;
11439 vinfos[1].foffset = j4;
11440 vinfos[1].indices[0] = _ij4[0];
11441 vinfos[1].indices[1] = _ij4[1];
11442 vinfos[1].maxsolutions = _nj4;
11443 vinfos[2].jointtype = 1;
11444 vinfos[2].foffset = j5;
11445 vinfos[2].indices[0] = _ij5[0];
11446 vinfos[2].indices[1] = _ij5[1];
11447 vinfos[2].maxsolutions = _nj5;
11448 vinfos[3].jointtype = 1;
11449 vinfos[3].foffset = j6;
11450 vinfos[3].indices[0] = _ij6[0];
11451 vinfos[3].indices[1] = _ij6[1];
11452 vinfos[3].maxsolutions = _nj6;
11453 vinfos[4].jointtype = 1;
11454 vinfos[4].foffset = j7;
11455 vinfos[4].indices[0] = _ij7[0];
11456 vinfos[4].indices[1] = _ij7[1];
11457 vinfos[4].maxsolutions = _nj7;
11458 vinfos[5].jointtype = 1;
11459 vinfos[5].foffset = j8;
11460 vinfos[5].indices[0] = _ij8[0];
11461 vinfos[5].indices[1] = _ij8[1];
11462 vinfos[5].maxsolutions = _nj8;
11463 std::vector<int> vfree(0);
11464 solutions.AddSolution(vinfos,vfree);
11465 }
11466 }
11467 }
11468 
11469 }
11470 
11471 }
11472 }
11473 }
11474 
11475 }
11476 
11477 }
11478 
11479 } else
11480 {
11481 {
11482 IkReal j5array[1], cj5array[1], sj5array[1];
11483 bool j5valid[1]={false};
11484 _nj5 = 1;
11485 IkReal x2546=((IkReal(4.00000000000000))*(npx));
11486 IkReal x2547=((IkReal(4.00000000000000))*(npy));
11487 if( IKabs(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(cj8)*(x2547)))+(((IkReal(-1.00000000000000))*(sj8)*(x2546))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2547)))+(((IkReal(-0.360000000000000))*(cj7)))+(((cj7)*(cj8)*(x2546))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(cj8)*(x2547)))+(((IkReal(-1.00000000000000))*(sj8)*(x2546)))))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2547)))+(((IkReal(-0.360000000000000))*(cj7)))+(((cj7)*(cj8)*(x2546)))))-1) <= IKFAST_SINCOS_THRESH )
11488  continue;
11489 j5array[0]=IKatan2(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(cj8)*(x2547)))+(((IkReal(-1.00000000000000))*(sj8)*(x2546)))))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2547)))+(((IkReal(-0.360000000000000))*(cj7)))+(((cj7)*(cj8)*(x2546)))));
11490 sj5array[0]=IKsin(j5array[0]);
11491 cj5array[0]=IKcos(j5array[0]);
11492 if( j5array[0] > IKPI )
11493 {
11494  j5array[0]-=IK2PI;
11495 }
11496 else if( j5array[0] < -IKPI )
11497 { j5array[0]+=IK2PI;
11498 }
11499 j5valid[0] = true;
11500 for(int ij5 = 0; ij5 < 1; ++ij5)
11501 {
11502 if( !j5valid[ij5] )
11503 {
11504  continue;
11505 }
11506 _ij5[0] = ij5; _ij5[1] = -1;
11507 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
11508 {
11509 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
11510 {
11511  j5valid[iij5]=false; _ij5[1] = iij5; break;
11512 }
11513 }
11514 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
11515 {
11516 IkReal evalcond[3];
11517 IkReal x2548=IKsin(j5);
11518 IkReal x2549=((IkReal(1.00000000000000))*(sj7));
11519 IkReal x2550=((npy)*(sj8));
11520 IkReal x2551=((cj8)*(npx));
11521 IkReal x2552=((IkReal(0.250000000000000))*(x2548));
11522 evalcond[0]=((((IkReal(-0.0300000000000000))*(sj6)))+(((IkReal(-0.0950000000000000))*(cj6)))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((sj6)*(x2552))));
11523 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2551)))+(((cj7)*(x2550)))+(((IkReal(0.250000000000000))*(IKcos(j5))))+(((IkReal(-1.00000000000000))*(npz)*(x2549))));
11524 evalcond[2]=((((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2549)*(x2551)))+(((IkReal(-1.00000000000000))*(cj6)*(x2552)))+(((IkReal(0.0300000000000000))*(cj6)))+(((IkReal(-0.0950000000000000))*(sj6)))+(((sj7)*(x2550)))+(((cj7)*(npz))));
11525 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
11526 {
11527 continue;
11528 }
11529 }
11530 
11531 {
11532 IkReal dummyeval[1];
11533 IkReal gconst46;
11534 gconst46=IKsign(((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5))))));
11535 dummyeval[0]=((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5)))));
11536 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
11537 {
11538 {
11539 IkReal dummyeval[1];
11540 IkReal gconst47;
11541 gconst47=IKsign(((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5))))));
11542 dummyeval[0]=((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5)))));
11543 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
11544 {
11545 {
11546 IkReal evalcond[9];
11547 IkReal x2553=((IkReal(1.00000000000000))*(sj7));
11548 IkReal x2554=((IkReal(1.00000000000000))*(cj3));
11549 IkReal x2555=((cj7)*(r02));
11550 IkReal x2556=((cj8)*(r00));
11551 IkReal x2557=((cj3)*(sj7));
11552 IkReal x2558=((cj8)*(npx));
11553 IkReal x2559=((r01)*(sj3));
11554 IkReal x2560=((cj7)*(sj8));
11555 IkReal x2561=((r11)*(sj8));
11556 IkReal x2562=((IkReal(1.00000000000000))*(cj7));
11557 IkReal x2563=((sj7)*(sj8));
11558 IkReal x2564=((cj8)*(r10));
11559 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
11560 evalcond[1]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(sj5))));
11561 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x2553)))+(((IkReal(-1.00000000000000))*(x2558)*(x2562)))+(((IkReal(0.250000000000000))*(cj5)))+(((npy)*(x2560))));
11562 evalcond[3]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2554)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2554)))+(((cj8)*(x2559)))+(((r00)*(sj3)*(sj8))));
11563 evalcond[4]=((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x2553)))+(((cj7)*(r22)))+(((r21)*(x2563))));
11564 evalcond[5]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x2563)))+(((cj7)*(npz)))+(((IkReal(-1.00000000000000))*(x2553)*(x2558))));
11565 evalcond[6]=((((cj3)*(cj7)*(x2564)))+(((r12)*(x2557)))+(((x2559)*(x2560)))+(((IkReal(-1.00000000000000))*(r11)*(x2554)*(x2560)))+(((IkReal(-1.00000000000000))*(sj3)*(x2556)*(x2562)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x2553))));
11566 evalcond[7]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x2553)*(x2561)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x2554)))+(((x2559)*(x2563)))+(((x2557)*(x2564)))+(((sj3)*(x2555)))+(((IkReal(-1.00000000000000))*(sj3)*(x2553)*(x2556))));
11567 evalcond[8]=((((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x2553)))+(((IkReal(-1.00000000000000))*(x2554)*(x2555)))+(((x2556)*(x2557)))+(((IkReal(-1.00000000000000))*(sj3)*(x2553)*(x2561)))+(((sj3)*(sj7)*(x2564)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2562))));
11568 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
11569 {
11570 {
11571 IkReal dummyeval[1];
11572 IkReal gconst48;
11573 gconst48=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
11574 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
11575 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
11576 {
11577 {
11578 IkReal dummyeval[1];
11579 IkReal gconst49;
11580 gconst49=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
11581 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
11582 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
11583 {
11584 continue;
11585 
11586 } else
11587 {
11588 {
11589 IkReal j4array[1], cj4array[1], sj4array[1];
11590 bool j4valid[1]={false};
11591 _nj4 = 1;
11592 IkReal x2565=((cj8)*(sj5));
11593 IkReal x2566=((cj3)*(r01));
11594 IkReal x2567=((IkReal(1.00000000000000))*(cj5));
11595 IkReal x2568=((r11)*(sj3));
11596 IkReal x2569=((sj5)*(sj8));
11597 IkReal x2570=((r10)*(sj3));
11598 IkReal x2571=((cj3)*(r00)*(sj8));
11599 if( IKabs(((gconst49)*(((((cj5)*(r20)*(sj8)))+(((x2565)*(x2568)))+(((x2565)*(x2566)))+(((cj3)*(r00)*(x2569)))+(((x2569)*(x2570)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((r20)*(x2569)))+(((IkReal(-1.00000000000000))*(cj8)*(x2567)*(x2568)))+(((IkReal(-1.00000000000000))*(x2567)*(x2571)))+(((IkReal(-1.00000000000000))*(cj8)*(x2566)*(x2567)))+(((IkReal(-1.00000000000000))*(sj8)*(x2567)*(x2570)))+(((r21)*(x2565))))))) < IKFAST_ATAN2_MAGTHRESH )
11600  continue;
11601 j4array[0]=IKatan2(((gconst49)*(((((cj5)*(r20)*(sj8)))+(((x2565)*(x2568)))+(((x2565)*(x2566)))+(((cj3)*(r00)*(x2569)))+(((x2569)*(x2570)))+(((cj5)*(cj8)*(r21)))))), ((gconst49)*(((((r20)*(x2569)))+(((IkReal(-1.00000000000000))*(cj8)*(x2567)*(x2568)))+(((IkReal(-1.00000000000000))*(x2567)*(x2571)))+(((IkReal(-1.00000000000000))*(cj8)*(x2566)*(x2567)))+(((IkReal(-1.00000000000000))*(sj8)*(x2567)*(x2570)))+(((r21)*(x2565)))))));
11602 sj4array[0]=IKsin(j4array[0]);
11603 cj4array[0]=IKcos(j4array[0]);
11604 if( j4array[0] > IKPI )
11605 {
11606  j4array[0]-=IK2PI;
11607 }
11608 else if( j4array[0] < -IKPI )
11609 { j4array[0]+=IK2PI;
11610 }
11611 j4valid[0] = true;
11612 for(int ij4 = 0; ij4 < 1; ++ij4)
11613 {
11614 if( !j4valid[ij4] )
11615 {
11616  continue;
11617 }
11618 _ij4[0] = ij4; _ij4[1] = -1;
11619 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11620 {
11621 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11622 {
11623  j4valid[iij4]=false; _ij4[1] = iij4; break;
11624 }
11625 }
11626 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11627 {
11628 IkReal evalcond[4];
11629 IkReal x2572=IKsin(j4);
11630 IkReal x2573=IKcos(j4);
11631 IkReal x2574=((IkReal(1.00000000000000))*(cj8));
11632 IkReal x2575=((cj3)*(r01));
11633 IkReal x2576=((cj3)*(r00));
11634 IkReal x2577=((cj7)*(cj8));
11635 IkReal x2578=((IkReal(1.00000000000000))*(cj5));
11636 IkReal x2579=((IkReal(1.00000000000000))*(sj8));
11637 IkReal x2580=((r11)*(sj3));
11638 IkReal x2581=((r10)*(sj3));
11639 IkReal x2582=((sj5)*(x2572));
11640 IkReal x2583=((sj5)*(x2573));
11641 IkReal x2584=((x2573)*(x2578));
11642 evalcond[0]=((((IkReal(-1.00000000000000))*(x2583)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2572)*(x2578)))+(((r20)*(sj8))));
11643 evalcond[1]=((x2582)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2574)))+(((IkReal(-1.00000000000000))*(x2584)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
11644 evalcond[2]=((x2582)+(((IkReal(-1.00000000000000))*(x2579)*(x2581)))+(((IkReal(-1.00000000000000))*(x2584)))+(((IkReal(-1.00000000000000))*(x2574)*(x2575)))+(((IkReal(-1.00000000000000))*(x2574)*(x2580)))+(((IkReal(-1.00000000000000))*(x2576)*(x2579))));
11645 evalcond[3]=((((r12)*(sj3)*(sj7)))+(x2583)+(((IkReal(-1.00000000000000))*(cj7)*(x2579)*(x2580)))+(((cj5)*(x2572)))+(((IkReal(-1.00000000000000))*(cj7)*(x2575)*(x2579)))+(((cj3)*(r02)*(sj7)))+(((x2577)*(x2581)))+(((x2576)*(x2577))));
11646 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
11647 {
11648 continue;
11649 }
11650 }
11651 
11652 {
11653 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11654 vinfos[0].jointtype = 1;
11655 vinfos[0].foffset = j3;
11656 vinfos[0].indices[0] = _ij3[0];
11657 vinfos[0].indices[1] = _ij3[1];
11658 vinfos[0].maxsolutions = _nj3;
11659 vinfos[1].jointtype = 1;
11660 vinfos[1].foffset = j4;
11661 vinfos[1].indices[0] = _ij4[0];
11662 vinfos[1].indices[1] = _ij4[1];
11663 vinfos[1].maxsolutions = _nj4;
11664 vinfos[2].jointtype = 1;
11665 vinfos[2].foffset = j5;
11666 vinfos[2].indices[0] = _ij5[0];
11667 vinfos[2].indices[1] = _ij5[1];
11668 vinfos[2].maxsolutions = _nj5;
11669 vinfos[3].jointtype = 1;
11670 vinfos[3].foffset = j6;
11671 vinfos[3].indices[0] = _ij6[0];
11672 vinfos[3].indices[1] = _ij6[1];
11673 vinfos[3].maxsolutions = _nj6;
11674 vinfos[4].jointtype = 1;
11675 vinfos[4].foffset = j7;
11676 vinfos[4].indices[0] = _ij7[0];
11677 vinfos[4].indices[1] = _ij7[1];
11678 vinfos[4].maxsolutions = _nj7;
11679 vinfos[5].jointtype = 1;
11680 vinfos[5].foffset = j8;
11681 vinfos[5].indices[0] = _ij8[0];
11682 vinfos[5].indices[1] = _ij8[1];
11683 vinfos[5].maxsolutions = _nj8;
11684 std::vector<int> vfree(0);
11685 solutions.AddSolution(vinfos,vfree);
11686 }
11687 }
11688 }
11689 
11690 }
11691 
11692 }
11693 
11694 } else
11695 {
11696 {
11697 IkReal j4array[1], cj4array[1], sj4array[1];
11698 bool j4valid[1]={false};
11699 _nj4 = 1;
11700 IkReal x2585=((sj5)*(sj8));
11701 IkReal x2586=((IkReal(1.00000000000000))*(cj7));
11702 IkReal x2587=((r22)*(sj7));
11703 IkReal x2588=((cj8)*(sj5));
11704 IkReal x2589=((cj5)*(cj8));
11705 IkReal x2590=((cj5)*(sj8));
11706 if( IKabs(((gconst48)*(((((sj5)*(x2587)))+(((IkReal(-1.00000000000000))*(r21)*(x2585)*(x2586)))+(((cj7)*(r20)*(x2588)))+(((r20)*(x2590)))+(((r21)*(x2589))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((IkReal(-1.00000000000000))*(r20)*(x2586)*(x2589)))+(((r20)*(x2585)))+(((cj7)*(r21)*(x2590)))+(((IkReal(-1.00000000000000))*(cj5)*(x2587)))+(((r21)*(x2588))))))) < IKFAST_ATAN2_MAGTHRESH )
11707  continue;
11708 j4array[0]=IKatan2(((gconst48)*(((((sj5)*(x2587)))+(((IkReal(-1.00000000000000))*(r21)*(x2585)*(x2586)))+(((cj7)*(r20)*(x2588)))+(((r20)*(x2590)))+(((r21)*(x2589)))))), ((gconst48)*(((((IkReal(-1.00000000000000))*(r20)*(x2586)*(x2589)))+(((r20)*(x2585)))+(((cj7)*(r21)*(x2590)))+(((IkReal(-1.00000000000000))*(cj5)*(x2587)))+(((r21)*(x2588)))))));
11709 sj4array[0]=IKsin(j4array[0]);
11710 cj4array[0]=IKcos(j4array[0]);
11711 if( j4array[0] > IKPI )
11712 {
11713  j4array[0]-=IK2PI;
11714 }
11715 else if( j4array[0] < -IKPI )
11716 { j4array[0]+=IK2PI;
11717 }
11718 j4valid[0] = true;
11719 for(int ij4 = 0; ij4 < 1; ++ij4)
11720 {
11721 if( !j4valid[ij4] )
11722 {
11723  continue;
11724 }
11725 _ij4[0] = ij4; _ij4[1] = -1;
11726 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11727 {
11728 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11729 {
11730  j4valid[iij4]=false; _ij4[1] = iij4; break;
11731 }
11732 }
11733 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11734 {
11735 IkReal evalcond[4];
11736 IkReal x2591=IKsin(j4);
11737 IkReal x2592=IKcos(j4);
11738 IkReal x2593=((IkReal(1.00000000000000))*(cj8));
11739 IkReal x2594=((cj3)*(r01));
11740 IkReal x2595=((cj3)*(r00));
11741 IkReal x2596=((cj7)*(cj8));
11742 IkReal x2597=((IkReal(1.00000000000000))*(cj5));
11743 IkReal x2598=((IkReal(1.00000000000000))*(sj8));
11744 IkReal x2599=((r11)*(sj3));
11745 IkReal x2600=((r10)*(sj3));
11746 IkReal x2601=((sj5)*(x2591));
11747 IkReal x2602=((sj5)*(x2592));
11748 IkReal x2603=((x2592)*(x2597));
11749 evalcond[0]=((((IkReal(-1.00000000000000))*(x2602)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2591)*(x2597)))+(((r20)*(sj8))));
11750 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2593)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(x2603)))+(x2601));
11751 evalcond[2]=((((IkReal(-1.00000000000000))*(x2593)*(x2594)))+(((IkReal(-1.00000000000000))*(x2593)*(x2599)))+(((IkReal(-1.00000000000000))*(x2595)*(x2598)))+(((IkReal(-1.00000000000000))*(x2598)*(x2600)))+(((IkReal(-1.00000000000000))*(x2603)))+(x2601));
11752 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x2596)*(x2600)))+(((IkReal(-1.00000000000000))*(cj7)*(x2594)*(x2598)))+(((cj3)*(r02)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2598)*(x2599)))+(((x2595)*(x2596)))+(((cj5)*(x2591)))+(x2602));
11753 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
11754 {
11755 continue;
11756 }
11757 }
11758 
11759 {
11760 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11761 vinfos[0].jointtype = 1;
11762 vinfos[0].foffset = j3;
11763 vinfos[0].indices[0] = _ij3[0];
11764 vinfos[0].indices[1] = _ij3[1];
11765 vinfos[0].maxsolutions = _nj3;
11766 vinfos[1].jointtype = 1;
11767 vinfos[1].foffset = j4;
11768 vinfos[1].indices[0] = _ij4[0];
11769 vinfos[1].indices[1] = _ij4[1];
11770 vinfos[1].maxsolutions = _nj4;
11771 vinfos[2].jointtype = 1;
11772 vinfos[2].foffset = j5;
11773 vinfos[2].indices[0] = _ij5[0];
11774 vinfos[2].indices[1] = _ij5[1];
11775 vinfos[2].maxsolutions = _nj5;
11776 vinfos[3].jointtype = 1;
11777 vinfos[3].foffset = j6;
11778 vinfos[3].indices[0] = _ij6[0];
11779 vinfos[3].indices[1] = _ij6[1];
11780 vinfos[3].maxsolutions = _nj6;
11781 vinfos[4].jointtype = 1;
11782 vinfos[4].foffset = j7;
11783 vinfos[4].indices[0] = _ij7[0];
11784 vinfos[4].indices[1] = _ij7[1];
11785 vinfos[4].maxsolutions = _nj7;
11786 vinfos[5].jointtype = 1;
11787 vinfos[5].foffset = j8;
11788 vinfos[5].indices[0] = _ij8[0];
11789 vinfos[5].indices[1] = _ij8[1];
11790 vinfos[5].maxsolutions = _nj8;
11791 std::vector<int> vfree(0);
11792 solutions.AddSolution(vinfos,vfree);
11793 }
11794 }
11795 }
11796 
11797 }
11798 
11799 }
11800 
11801 } else
11802 {
11803 IkReal x2604=((IkReal(1.00000000000000))*(sj7));
11804 IkReal x2605=((IkReal(1.00000000000000))*(cj3));
11805 IkReal x2606=((cj7)*(r02));
11806 IkReal x2607=((cj8)*(r00));
11807 IkReal x2608=((cj3)*(sj7));
11808 IkReal x2609=((cj8)*(npx));
11809 IkReal x2610=((r01)*(sj3));
11810 IkReal x2611=((cj7)*(sj8));
11811 IkReal x2612=((r11)*(sj8));
11812 IkReal x2613=((IkReal(1.00000000000000))*(cj7));
11813 IkReal x2614=((sj7)*(sj8));
11814 IkReal x2615=((cj8)*(r10));
11815 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
11816 evalcond[1]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(sj5))));
11817 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(x2609)*(x2613)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x2604)))+(((npy)*(x2611))));
11818 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2605)))+(((cj8)*(x2610)))+(((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2605)))+(((r00)*(sj3)*(sj8))));
11819 evalcond[4]=((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x2604)))+(((cj7)*(r22)))+(((r21)*(x2614))));
11820 evalcond[5]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((cj7)*(npz)))+(((npy)*(x2614)))+(((IkReal(-1.00000000000000))*(x2604)*(x2609))));
11821 evalcond[6]=((((x2610)*(x2611)))+(((IkReal(-1.00000000000000))*(r11)*(x2605)*(x2611)))+(((IkReal(-1.00000000000000))*(sj3)*(x2607)*(x2613)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x2604)))+(((r12)*(x2608)))+(((cj3)*(cj7)*(x2615))));
11822 evalcond[7]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(sj3)*(x2604)*(x2607)))+(((x2610)*(x2614)))+(((sj3)*(x2606)))+(((IkReal(-1.00000000000000))*(cj3)*(x2604)*(x2612)))+(((x2608)*(x2615)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x2605))));
11823 evalcond[8]=((((x2607)*(x2608)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x2604)))+(((IkReal(-1.00000000000000))*(sj3)*(x2604)*(x2612)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2613)))+(((sj3)*(sj7)*(x2615)))+(((IkReal(-1.00000000000000))*(x2605)*(x2606))));
11824 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
11825 {
11826 {
11827 IkReal dummyeval[1];
11828 IkReal gconst50;
11829 gconst50=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
11830 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
11831 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
11832 {
11833 {
11834 IkReal dummyeval[1];
11835 IkReal gconst51;
11836 gconst51=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
11837 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
11838 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
11839 {
11840 continue;
11841 
11842 } else
11843 {
11844 {
11845 IkReal j4array[1], cj4array[1], sj4array[1];
11846 bool j4valid[1]={false};
11847 _nj4 = 1;
11848 IkReal x2616=((IkReal(1.00000000000000))*(sj5));
11849 IkReal x2617=((r20)*(sj8));
11850 IkReal x2618=((cj5)*(cj8));
11851 IkReal x2619=((r11)*(sj3));
11852 IkReal x2620=((cj3)*(r01));
11853 IkReal x2621=((cj3)*(r00)*(sj8));
11854 IkReal x2622=((r10)*(sj3)*(sj8));
11855 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(cj8)*(x2616)*(x2619)))+(((IkReal(-1.00000000000000))*(cj8)*(x2616)*(x2620)))+(((IkReal(-1.00000000000000))*(r21)*(x2618)))+(((IkReal(-1.00000000000000))*(cj5)*(x2617)))+(((IkReal(-1.00000000000000))*(x2616)*(x2622)))+(((IkReal(-1.00000000000000))*(x2616)*(x2621))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((cj5)*(x2622)))+(((cj5)*(x2621)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2616)))+(((x2618)*(x2620)))+(((x2618)*(x2619)))+(((IkReal(-1.00000000000000))*(x2616)*(x2617))))))) < IKFAST_ATAN2_MAGTHRESH )
11856  continue;
11857 j4array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(cj8)*(x2616)*(x2619)))+(((IkReal(-1.00000000000000))*(cj8)*(x2616)*(x2620)))+(((IkReal(-1.00000000000000))*(r21)*(x2618)))+(((IkReal(-1.00000000000000))*(cj5)*(x2617)))+(((IkReal(-1.00000000000000))*(x2616)*(x2622)))+(((IkReal(-1.00000000000000))*(x2616)*(x2621)))))), ((gconst51)*(((((cj5)*(x2622)))+(((cj5)*(x2621)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2616)))+(((x2618)*(x2620)))+(((x2618)*(x2619)))+(((IkReal(-1.00000000000000))*(x2616)*(x2617)))))));
11858 sj4array[0]=IKsin(j4array[0]);
11859 cj4array[0]=IKcos(j4array[0]);
11860 if( j4array[0] > IKPI )
11861 {
11862  j4array[0]-=IK2PI;
11863 }
11864 else if( j4array[0] < -IKPI )
11865 { j4array[0]+=IK2PI;
11866 }
11867 j4valid[0] = true;
11868 for(int ij4 = 0; ij4 < 1; ++ij4)
11869 {
11870 if( !j4valid[ij4] )
11871 {
11872  continue;
11873 }
11874 _ij4[0] = ij4; _ij4[1] = -1;
11875 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11876 {
11877 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11878 {
11879  j4valid[iij4]=false; _ij4[1] = iij4; break;
11880 }
11881 }
11882 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11883 {
11884 IkReal evalcond[4];
11885 IkReal x2623=IKsin(j4);
11886 IkReal x2624=IKcos(j4);
11887 IkReal x2625=((IkReal(1.00000000000000))*(cj8));
11888 IkReal x2626=((cj3)*(r01));
11889 IkReal x2627=((cj3)*(r00));
11890 IkReal x2628=((cj7)*(cj8));
11891 IkReal x2629=((r11)*(sj3));
11892 IkReal x2630=((IkReal(1.00000000000000))*(sj8));
11893 IkReal x2631=((r10)*(sj3));
11894 IkReal x2632=((sj5)*(x2624));
11895 IkReal x2633=((cj5)*(x2623));
11896 IkReal x2634=((cj5)*(x2624));
11897 IkReal x2635=((sj5)*(x2623));
11898 IkReal x2636=((x2633)+(x2632));
11899 evalcond[0]=((((cj8)*(r21)))+(((r20)*(sj8)))+(x2636));
11900 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2625)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x2634)))+(((cj7)*(r21)*(sj8)))+(x2635));
11901 evalcond[2]=((((IkReal(-1.00000000000000))*(x2625)*(x2626)))+(((IkReal(-1.00000000000000))*(x2625)*(x2629)))+(((IkReal(-1.00000000000000))*(x2630)*(x2631)))+(((IkReal(-1.00000000000000))*(x2635)))+(x2634)+(((IkReal(-1.00000000000000))*(x2627)*(x2630))));
11902 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x2627)*(x2628)))+(((IkReal(-1.00000000000000))*(cj7)*(x2626)*(x2630)))+(((x2628)*(x2631)))+(((cj3)*(r02)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2629)*(x2630)))+(x2636));
11903 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
11904 {
11905 continue;
11906 }
11907 }
11908 
11909 {
11910 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11911 vinfos[0].jointtype = 1;
11912 vinfos[0].foffset = j3;
11913 vinfos[0].indices[0] = _ij3[0];
11914 vinfos[0].indices[1] = _ij3[1];
11915 vinfos[0].maxsolutions = _nj3;
11916 vinfos[1].jointtype = 1;
11917 vinfos[1].foffset = j4;
11918 vinfos[1].indices[0] = _ij4[0];
11919 vinfos[1].indices[1] = _ij4[1];
11920 vinfos[1].maxsolutions = _nj4;
11921 vinfos[2].jointtype = 1;
11922 vinfos[2].foffset = j5;
11923 vinfos[2].indices[0] = _ij5[0];
11924 vinfos[2].indices[1] = _ij5[1];
11925 vinfos[2].maxsolutions = _nj5;
11926 vinfos[3].jointtype = 1;
11927 vinfos[3].foffset = j6;
11928 vinfos[3].indices[0] = _ij6[0];
11929 vinfos[3].indices[1] = _ij6[1];
11930 vinfos[3].maxsolutions = _nj6;
11931 vinfos[4].jointtype = 1;
11932 vinfos[4].foffset = j7;
11933 vinfos[4].indices[0] = _ij7[0];
11934 vinfos[4].indices[1] = _ij7[1];
11935 vinfos[4].maxsolutions = _nj7;
11936 vinfos[5].jointtype = 1;
11937 vinfos[5].foffset = j8;
11938 vinfos[5].indices[0] = _ij8[0];
11939 vinfos[5].indices[1] = _ij8[1];
11940 vinfos[5].maxsolutions = _nj8;
11941 std::vector<int> vfree(0);
11942 solutions.AddSolution(vinfos,vfree);
11943 }
11944 }
11945 }
11946 
11947 }
11948 
11949 }
11950 
11951 } else
11952 {
11953 {
11954 IkReal j4array[1], cj4array[1], sj4array[1];
11955 bool j4valid[1]={false};
11956 _nj4 = 1;
11957 IkReal x2637=((cj8)*(sj5));
11958 IkReal x2638=((sj5)*(sj8));
11959 IkReal x2639=((r22)*(sj7));
11960 IkReal x2640=((cj7)*(r20));
11961 IkReal x2641=((cj5)*(cj8));
11962 IkReal x2642=((cj7)*(r21));
11963 IkReal x2643=((cj5)*(sj8));
11964 if( IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(x2637)*(x2640)))+(((r21)*(x2641)))+(((IkReal(-1.00000000000000))*(sj5)*(x2639)))+(((x2638)*(x2642)))+(((r20)*(x2643))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((r21)*(x2637)))+(((cj5)*(x2639)))+(((r20)*(x2638)))+(((x2640)*(x2641)))+(((IkReal(-1.00000000000000))*(x2642)*(x2643))))))) < IKFAST_ATAN2_MAGTHRESH )
11965  continue;
11966 j4array[0]=IKatan2(((gconst50)*(((((IkReal(-1.00000000000000))*(x2637)*(x2640)))+(((r21)*(x2641)))+(((IkReal(-1.00000000000000))*(sj5)*(x2639)))+(((x2638)*(x2642)))+(((r20)*(x2643)))))), ((gconst50)*(((((r21)*(x2637)))+(((cj5)*(x2639)))+(((r20)*(x2638)))+(((x2640)*(x2641)))+(((IkReal(-1.00000000000000))*(x2642)*(x2643)))))));
11967 sj4array[0]=IKsin(j4array[0]);
11968 cj4array[0]=IKcos(j4array[0]);
11969 if( j4array[0] > IKPI )
11970 {
11971  j4array[0]-=IK2PI;
11972 }
11973 else if( j4array[0] < -IKPI )
11974 { j4array[0]+=IK2PI;
11975 }
11976 j4valid[0] = true;
11977 for(int ij4 = 0; ij4 < 1; ++ij4)
11978 {
11979 if( !j4valid[ij4] )
11980 {
11981  continue;
11982 }
11983 _ij4[0] = ij4; _ij4[1] = -1;
11984 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11985 {
11986 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11987 {
11988  j4valid[iij4]=false; _ij4[1] = iij4; break;
11989 }
11990 }
11991 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11992 {
11993 IkReal evalcond[4];
11994 IkReal x2644=IKsin(j4);
11995 IkReal x2645=IKcos(j4);
11996 IkReal x2646=((IkReal(1.00000000000000))*(cj8));
11997 IkReal x2647=((cj3)*(r01));
11998 IkReal x2648=((cj3)*(r00));
11999 IkReal x2649=((cj7)*(cj8));
12000 IkReal x2650=((r11)*(sj3));
12001 IkReal x2651=((IkReal(1.00000000000000))*(sj8));
12002 IkReal x2652=((r10)*(sj3));
12003 IkReal x2653=((sj5)*(x2645));
12004 IkReal x2654=((cj5)*(x2644));
12005 IkReal x2655=((cj5)*(x2645));
12006 IkReal x2656=((sj5)*(x2644));
12007 IkReal x2657=((x2653)+(x2654));
12008 evalcond[0]=((((cj8)*(r21)))+(((r20)*(sj8)))+(x2657));
12009 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2646)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(x2655)))+(x2656));
12010 evalcond[2]=((((IkReal(-1.00000000000000))*(x2651)*(x2652)))+(((IkReal(-1.00000000000000))*(x2646)*(x2647)))+(((IkReal(-1.00000000000000))*(x2646)*(x2650)))+(((IkReal(-1.00000000000000))*(x2648)*(x2651)))+(((IkReal(-1.00000000000000))*(x2656)))+(x2655));
12011 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x2649)*(x2652)))+(((x2648)*(x2649)))+(((IkReal(-1.00000000000000))*(cj7)*(x2650)*(x2651)))+(((cj3)*(r02)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2647)*(x2651)))+(x2657));
12012 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
12013 {
12014 continue;
12015 }
12016 }
12017 
12018 {
12019 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12020 vinfos[0].jointtype = 1;
12021 vinfos[0].foffset = j3;
12022 vinfos[0].indices[0] = _ij3[0];
12023 vinfos[0].indices[1] = _ij3[1];
12024 vinfos[0].maxsolutions = _nj3;
12025 vinfos[1].jointtype = 1;
12026 vinfos[1].foffset = j4;
12027 vinfos[1].indices[0] = _ij4[0];
12028 vinfos[1].indices[1] = _ij4[1];
12029 vinfos[1].maxsolutions = _nj4;
12030 vinfos[2].jointtype = 1;
12031 vinfos[2].foffset = j5;
12032 vinfos[2].indices[0] = _ij5[0];
12033 vinfos[2].indices[1] = _ij5[1];
12034 vinfos[2].maxsolutions = _nj5;
12035 vinfos[3].jointtype = 1;
12036 vinfos[3].foffset = j6;
12037 vinfos[3].indices[0] = _ij6[0];
12038 vinfos[3].indices[1] = _ij6[1];
12039 vinfos[3].maxsolutions = _nj6;
12040 vinfos[4].jointtype = 1;
12041 vinfos[4].foffset = j7;
12042 vinfos[4].indices[0] = _ij7[0];
12043 vinfos[4].indices[1] = _ij7[1];
12044 vinfos[4].maxsolutions = _nj7;
12045 vinfos[5].jointtype = 1;
12046 vinfos[5].foffset = j8;
12047 vinfos[5].indices[0] = _ij8[0];
12048 vinfos[5].indices[1] = _ij8[1];
12049 vinfos[5].maxsolutions = _nj8;
12050 std::vector<int> vfree(0);
12051 solutions.AddSolution(vinfos,vfree);
12052 }
12053 }
12054 }
12055 
12056 }
12057 
12058 }
12059 
12060 } else
12061 {
12062 IkReal x2658=((cj3)*(cj8));
12063 IkReal x2659=((IkReal(1.00000000000000))*(sj7));
12064 IkReal x2660=((cj8)*(npx));
12065 IkReal x2661=((cj8)*(sj3));
12066 IkReal x2662=((npy)*(sj8));
12067 IkReal x2663=((r02)*(sj3));
12068 IkReal x2664=((IkReal(1.00000000000000))*(r11));
12069 IkReal x2665=((cj3)*(r12));
12070 IkReal x2666=((IkReal(1.00000000000000))*(cj7));
12071 IkReal x2667=((sj3)*(sj8));
12072 IkReal x2668=((IkReal(1.00000000000000))*(cj3)*(sj8));
12073 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
12074 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
12075 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
12076 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(x2660)*(x2666)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((cj7)*(x2662)))+(((IkReal(-1.00000000000000))*(npz)*(x2659))));
12077 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x2658)*(x2664)))+(((r00)*(x2667)))+(((r01)*(x2661)))+(((IkReal(-1.00000000000000))*(r10)*(x2668))));
12078 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x2659)*(x2660)))+(((sj7)*(x2662)))+(((cj7)*(npz)))+(((IkReal(-0.250000000000000))*(sj5))));
12079 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x2658)))+(((IkReal(-1.00000000000000))*(r00)*(x2668)))+(((IkReal(-1.00000000000000))*(r10)*(x2667)))+(((IkReal(-1.00000000000000))*(x2661)*(x2664))));
12080 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(x2661)*(x2666)))+(((cj7)*(r01)*(x2667)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x2664)))+(((IkReal(-1.00000000000000))*(x2659)*(x2663)))+(((sj7)*(x2665)))+(((cj7)*(r10)*(x2658))));
12081 evalcond[8]=((((r10)*(sj7)*(x2658)))+(((r01)*(sj7)*(x2667)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x2659)))+(((cj7)*(x2663)))+(((IkReal(-1.00000000000000))*(x2665)*(x2666)))+(((IkReal(-1.00000000000000))*(r00)*(x2659)*(x2661))));
12082 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
12083 {
12084 {
12085 IkReal dummyeval[1];
12086 IkReal gconst52;
12087 gconst52=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
12088 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
12089 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12090 {
12091 {
12092 IkReal dummyeval[1];
12093 IkReal gconst53;
12094 gconst53=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
12095 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
12096 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12097 {
12098 continue;
12099 
12100 } else
12101 {
12102 {
12103 IkReal j4array[1], cj4array[1], sj4array[1];
12104 bool j4valid[1]={false};
12105 _nj4 = 1;
12106 IkReal x2669=((cj3)*(cj5));
12107 IkReal x2670=((r02)*(sj7));
12108 IkReal x2671=((cj5)*(sj7));
12109 IkReal x2672=((cj3)*(sj5));
12110 IkReal x2673=((r11)*(sj3));
12111 IkReal x2674=((r10)*(sj3));
12112 IkReal x2675=((r12)*(sj3));
12113 IkReal x2676=((sj5)*(sj7));
12114 IkReal x2677=((cj7)*(cj8)*(sj5));
12115 IkReal x2678=((IkReal(1.00000000000000))*(cj7)*(sj8));
12116 IkReal x2679=((cj5)*(cj7)*(cj8));
12117 if( IKabs(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r01)*(x2669)*(x2678)))+(((IkReal(-1.00000000000000))*(r22)*(x2676)))+(((IkReal(-1.00000000000000))*(cj5)*(x2673)*(x2678)))+(((x2669)*(x2670)))+(((x2671)*(x2675)))+(((IkReal(-1.00000000000000))*(r20)*(x2677)))+(((cj7)*(cj8)*(r00)*(x2669)))+(((x2674)*(x2679))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((IkReal(-1.00000000000000))*(r01)*(x2672)*(x2678)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2678)))+(((IkReal(-1.00000000000000))*(sj5)*(x2673)*(x2678)))+(((r22)*(x2671)))+(((x2675)*(x2676)))+(((x2670)*(x2672)))+(((r20)*(x2679)))+(((cj7)*(cj8)*(r00)*(x2672)))+(((x2674)*(x2677))))))) < IKFAST_ATAN2_MAGTHRESH )
12118  continue;
12119 j4array[0]=IKatan2(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r01)*(x2669)*(x2678)))+(((IkReal(-1.00000000000000))*(r22)*(x2676)))+(((IkReal(-1.00000000000000))*(cj5)*(x2673)*(x2678)))+(((x2669)*(x2670)))+(((x2671)*(x2675)))+(((IkReal(-1.00000000000000))*(r20)*(x2677)))+(((cj7)*(cj8)*(r00)*(x2669)))+(((x2674)*(x2679)))))), ((gconst53)*(((((IkReal(-1.00000000000000))*(r01)*(x2672)*(x2678)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2678)))+(((IkReal(-1.00000000000000))*(sj5)*(x2673)*(x2678)))+(((r22)*(x2671)))+(((x2675)*(x2676)))+(((x2670)*(x2672)))+(((r20)*(x2679)))+(((cj7)*(cj8)*(r00)*(x2672)))+(((x2674)*(x2677)))))));
12120 sj4array[0]=IKsin(j4array[0]);
12121 cj4array[0]=IKcos(j4array[0]);
12122 if( j4array[0] > IKPI )
12123 {
12124  j4array[0]-=IK2PI;
12125 }
12126 else if( j4array[0] < -IKPI )
12127 { j4array[0]+=IK2PI;
12128 }
12129 j4valid[0] = true;
12130 for(int ij4 = 0; ij4 < 1; ++ij4)
12131 {
12132 if( !j4valid[ij4] )
12133 {
12134  continue;
12135 }
12136 _ij4[0] = ij4; _ij4[1] = -1;
12137 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12138 {
12139 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12140 {
12141  j4valid[iij4]=false; _ij4[1] = iij4; break;
12142 }
12143 }
12144 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12145 {
12146 IkReal evalcond[4];
12147 IkReal x2680=IKcos(j4);
12148 IkReal x2681=IKsin(j4);
12149 IkReal x2682=((IkReal(1.00000000000000))*(cj7));
12150 IkReal x2683=((cj8)*(r20));
12151 IkReal x2684=((cj3)*(r02));
12152 IkReal x2685=((IkReal(1.00000000000000))*(sj7));
12153 IkReal x2686=((sj3)*(sj7));
12154 IkReal x2687=((r21)*(sj8));
12155 IkReal x2688=((cj8)*(r10));
12156 IkReal x2689=((sj5)*(x2680));
12157 IkReal x2690=((cj5)*(x2681));
12158 IkReal x2691=((r11)*(sj3)*(sj8));
12159 IkReal x2692=((cj3)*(cj8)*(r00));
12160 IkReal x2693=((cj5)*(x2680));
12161 IkReal x2694=((cj3)*(r01)*(sj8));
12162 IkReal x2695=((sj5)*(x2681));
12163 IkReal x2696=((x2689)+(x2690));
12164 evalcond[0]=((((cj7)*(x2687)))+(((IkReal(-1.00000000000000))*(r22)*(x2685)))+(((IkReal(-1.00000000000000))*(x2682)*(x2683)))+(((IkReal(-1.00000000000000))*(x2693)))+(x2695));
12165 evalcond[1]=((((IkReal(-1.00000000000000))*(x2683)*(x2685)))+(((sj7)*(x2687)))+(((cj7)*(r22)))+(x2696));
12166 evalcond[2]=((((cj7)*(sj3)*(x2688)))+(((cj7)*(x2692)))+(((sj7)*(x2684)))+(((IkReal(-1.00000000000000))*(x2682)*(x2694)))+(((IkReal(-1.00000000000000))*(x2682)*(x2691)))+(((r12)*(x2686)))+(x2696));
12167 evalcond[3]=((((sj7)*(x2692)))+(((IkReal(-1.00000000000000))*(x2682)*(x2684)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2682)))+(((x2686)*(x2688)))+(((IkReal(-1.00000000000000))*(x2695)))+(((IkReal(-1.00000000000000))*(x2685)*(x2691)))+(((IkReal(-1.00000000000000))*(x2685)*(x2694)))+(x2693));
12168 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
12169 {
12170 continue;
12171 }
12172 }
12173 
12174 {
12175 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12176 vinfos[0].jointtype = 1;
12177 vinfos[0].foffset = j3;
12178 vinfos[0].indices[0] = _ij3[0];
12179 vinfos[0].indices[1] = _ij3[1];
12180 vinfos[0].maxsolutions = _nj3;
12181 vinfos[1].jointtype = 1;
12182 vinfos[1].foffset = j4;
12183 vinfos[1].indices[0] = _ij4[0];
12184 vinfos[1].indices[1] = _ij4[1];
12185 vinfos[1].maxsolutions = _nj4;
12186 vinfos[2].jointtype = 1;
12187 vinfos[2].foffset = j5;
12188 vinfos[2].indices[0] = _ij5[0];
12189 vinfos[2].indices[1] = _ij5[1];
12190 vinfos[2].maxsolutions = _nj5;
12191 vinfos[3].jointtype = 1;
12192 vinfos[3].foffset = j6;
12193 vinfos[3].indices[0] = _ij6[0];
12194 vinfos[3].indices[1] = _ij6[1];
12195 vinfos[3].maxsolutions = _nj6;
12196 vinfos[4].jointtype = 1;
12197 vinfos[4].foffset = j7;
12198 vinfos[4].indices[0] = _ij7[0];
12199 vinfos[4].indices[1] = _ij7[1];
12200 vinfos[4].maxsolutions = _nj7;
12201 vinfos[5].jointtype = 1;
12202 vinfos[5].foffset = j8;
12203 vinfos[5].indices[0] = _ij8[0];
12204 vinfos[5].indices[1] = _ij8[1];
12205 vinfos[5].maxsolutions = _nj8;
12206 std::vector<int> vfree(0);
12207 solutions.AddSolution(vinfos,vfree);
12208 }
12209 }
12210 }
12211 
12212 }
12213 
12214 }
12215 
12216 } else
12217 {
12218 {
12219 IkReal j4array[1], cj4array[1], sj4array[1];
12220 bool j4valid[1]={false};
12221 _nj4 = 1;
12222 IkReal x2697=((r21)*(sj8));
12223 IkReal x2698=((sj5)*(sj7));
12224 IkReal x2699=((cj5)*(sj7));
12225 IkReal x2700=((cj5)*(cj7));
12226 IkReal x2701=((cj8)*(r20));
12227 IkReal x2702=((cj7)*(sj5));
12228 if( IKabs(((gconst52)*(((((r22)*(x2700)))+(((IkReal(-1.00000000000000))*(r22)*(x2698)))+(((x2697)*(x2702)))+(((x2697)*(x2699)))+(((IkReal(-1.00000000000000))*(x2699)*(x2701)))+(((IkReal(-1.00000000000000))*(x2701)*(x2702))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((r22)*(x2702)))+(((r22)*(x2699)))+(((x2697)*(x2698)))+(((IkReal(-1.00000000000000))*(x2697)*(x2700)))+(((x2700)*(x2701)))+(((IkReal(-1.00000000000000))*(x2698)*(x2701))))))) < IKFAST_ATAN2_MAGTHRESH )
12229  continue;
12230 j4array[0]=IKatan2(((gconst52)*(((((r22)*(x2700)))+(((IkReal(-1.00000000000000))*(r22)*(x2698)))+(((x2697)*(x2702)))+(((x2697)*(x2699)))+(((IkReal(-1.00000000000000))*(x2699)*(x2701)))+(((IkReal(-1.00000000000000))*(x2701)*(x2702)))))), ((gconst52)*(((((r22)*(x2702)))+(((r22)*(x2699)))+(((x2697)*(x2698)))+(((IkReal(-1.00000000000000))*(x2697)*(x2700)))+(((x2700)*(x2701)))+(((IkReal(-1.00000000000000))*(x2698)*(x2701)))))));
12231 sj4array[0]=IKsin(j4array[0]);
12232 cj4array[0]=IKcos(j4array[0]);
12233 if( j4array[0] > IKPI )
12234 {
12235  j4array[0]-=IK2PI;
12236 }
12237 else if( j4array[0] < -IKPI )
12238 { j4array[0]+=IK2PI;
12239 }
12240 j4valid[0] = true;
12241 for(int ij4 = 0; ij4 < 1; ++ij4)
12242 {
12243 if( !j4valid[ij4] )
12244 {
12245  continue;
12246 }
12247 _ij4[0] = ij4; _ij4[1] = -1;
12248 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12249 {
12250 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12251 {
12252  j4valid[iij4]=false; _ij4[1] = iij4; break;
12253 }
12254 }
12255 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12256 {
12257 IkReal evalcond[4];
12258 IkReal x2703=IKcos(j4);
12259 IkReal x2704=IKsin(j4);
12260 IkReal x2705=((IkReal(1.00000000000000))*(cj7));
12261 IkReal x2706=((cj8)*(r20));
12262 IkReal x2707=((cj3)*(r02));
12263 IkReal x2708=((IkReal(1.00000000000000))*(sj7));
12264 IkReal x2709=((sj3)*(sj7));
12265 IkReal x2710=((r21)*(sj8));
12266 IkReal x2711=((cj8)*(r10));
12267 IkReal x2712=((sj5)*(x2703));
12268 IkReal x2713=((cj5)*(x2704));
12269 IkReal x2714=((r11)*(sj3)*(sj8));
12270 IkReal x2715=((cj3)*(cj8)*(r00));
12271 IkReal x2716=((cj5)*(x2703));
12272 IkReal x2717=((cj3)*(r01)*(sj8));
12273 IkReal x2718=((sj5)*(x2704));
12274 IkReal x2719=((x2712)+(x2713));
12275 evalcond[0]=((x2718)+(((IkReal(-1.00000000000000))*(x2716)))+(((IkReal(-1.00000000000000))*(r22)*(x2708)))+(((IkReal(-1.00000000000000))*(x2705)*(x2706)))+(((cj7)*(x2710))));
12276 evalcond[1]=((x2719)+(((sj7)*(x2710)))+(((IkReal(-1.00000000000000))*(x2706)*(x2708)))+(((cj7)*(r22))));
12277 evalcond[2]=((x2719)+(((r12)*(x2709)))+(((cj7)*(x2715)))+(((cj7)*(sj3)*(x2711)))+(((IkReal(-1.00000000000000))*(x2705)*(x2717)))+(((IkReal(-1.00000000000000))*(x2705)*(x2714)))+(((sj7)*(x2707))));
12278 evalcond[3]=((x2716)+(((IkReal(-1.00000000000000))*(x2718)))+(((sj7)*(x2715)))+(((x2709)*(x2711)))+(((IkReal(-1.00000000000000))*(x2708)*(x2714)))+(((IkReal(-1.00000000000000))*(x2708)*(x2717)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2705)))+(((IkReal(-1.00000000000000))*(x2705)*(x2707))));
12279 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
12280 {
12281 continue;
12282 }
12283 }
12284 
12285 {
12286 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12287 vinfos[0].jointtype = 1;
12288 vinfos[0].foffset = j3;
12289 vinfos[0].indices[0] = _ij3[0];
12290 vinfos[0].indices[1] = _ij3[1];
12291 vinfos[0].maxsolutions = _nj3;
12292 vinfos[1].jointtype = 1;
12293 vinfos[1].foffset = j4;
12294 vinfos[1].indices[0] = _ij4[0];
12295 vinfos[1].indices[1] = _ij4[1];
12296 vinfos[1].maxsolutions = _nj4;
12297 vinfos[2].jointtype = 1;
12298 vinfos[2].foffset = j5;
12299 vinfos[2].indices[0] = _ij5[0];
12300 vinfos[2].indices[1] = _ij5[1];
12301 vinfos[2].maxsolutions = _nj5;
12302 vinfos[3].jointtype = 1;
12303 vinfos[3].foffset = j6;
12304 vinfos[3].indices[0] = _ij6[0];
12305 vinfos[3].indices[1] = _ij6[1];
12306 vinfos[3].maxsolutions = _nj6;
12307 vinfos[4].jointtype = 1;
12308 vinfos[4].foffset = j7;
12309 vinfos[4].indices[0] = _ij7[0];
12310 vinfos[4].indices[1] = _ij7[1];
12311 vinfos[4].maxsolutions = _nj7;
12312 vinfos[5].jointtype = 1;
12313 vinfos[5].foffset = j8;
12314 vinfos[5].indices[0] = _ij8[0];
12315 vinfos[5].indices[1] = _ij8[1];
12316 vinfos[5].maxsolutions = _nj8;
12317 std::vector<int> vfree(0);
12318 solutions.AddSolution(vinfos,vfree);
12319 }
12320 }
12321 }
12322 
12323 }
12324 
12325 }
12326 
12327 } else
12328 {
12329 IkReal x2720=((cj3)*(cj8));
12330 IkReal x2721=((IkReal(1.00000000000000))*(sj7));
12331 IkReal x2722=((cj8)*(npx));
12332 IkReal x2723=((cj8)*(sj3));
12333 IkReal x2724=((npy)*(sj8));
12334 IkReal x2725=((r02)*(sj3));
12335 IkReal x2726=((IkReal(1.00000000000000))*(r11));
12336 IkReal x2727=((cj3)*(r12));
12337 IkReal x2728=((IkReal(1.00000000000000))*(cj7));
12338 IkReal x2729=((sj3)*(sj8));
12339 IkReal x2730=((IkReal(1.00000000000000))*(cj3)*(sj8));
12340 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
12341 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
12342 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
12343 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x2721)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(x2722)*(x2728)))+(((IkReal(0.250000000000000))*(cj5)))+(((cj7)*(x2724))));
12344 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2720)*(x2726)))+(((r00)*(x2729)))+(((r01)*(x2723)))+(((IkReal(-1.00000000000000))*(r10)*(x2730))));
12345 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(0.250000000000000))*(sj5)))+(((IkReal(-1.00000000000000))*(x2721)*(x2722)))+(((sj7)*(x2724)))+(((cj7)*(npz))));
12346 evalcond[6]=((((IkReal(-1.00000000000000))*(x2723)*(x2726)))+(((IkReal(-1.00000000000000))*(r01)*(x2720)))+(((IkReal(-1.00000000000000))*(r10)*(x2729)))+(((IkReal(-1.00000000000000))*(r00)*(x2730))));
12347 evalcond[7]=((((cj7)*(r01)*(x2729)))+(((cj7)*(r10)*(x2720)))+(((IkReal(-1.00000000000000))*(r00)*(x2723)*(x2728)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x2726)))+(((IkReal(-1.00000000000000))*(x2721)*(x2725)))+(((sj7)*(x2727))));
12348 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(x2721)*(x2723)))+(((r01)*(sj7)*(x2729)))+(((IkReal(-1.00000000000000))*(x2727)*(x2728)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x2721)))+(((r10)*(sj7)*(x2720)))+(((cj7)*(x2725))));
12349 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
12350 {
12351 {
12352 IkReal dummyeval[1];
12353 IkReal gconst54;
12354 gconst54=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
12355 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
12356 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12357 {
12358 {
12359 IkReal dummyeval[1];
12360 IkReal gconst55;
12361 gconst55=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
12362 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
12363 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12364 {
12365 continue;
12366 
12367 } else
12368 {
12369 {
12370 IkReal j4array[1], cj4array[1], sj4array[1];
12371 bool j4valid[1]={false};
12372 _nj4 = 1;
12373 IkReal x2731=((cj3)*(cj5));
12374 IkReal x2732=((r02)*(sj7));
12375 IkReal x2733=((cj8)*(r00));
12376 IkReal x2734=((cj5)*(sj7));
12377 IkReal x2735=((cj5)*(sj3));
12378 IkReal x2736=((sj3)*(sj5));
12379 IkReal x2737=((IkReal(1.00000000000000))*(sj5));
12380 IkReal x2738=((cj3)*(cj7)*(sj5));
12381 IkReal x2739=((IkReal(1.00000000000000))*(cj7)*(sj8));
12382 IkReal x2740=((cj7)*(cj8)*(r10));
12383 IkReal x2741=((cj7)*(cj8)*(r20));
12384 if( IKabs(((gconst55)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r01)*(x2731)*(x2739)))+(((IkReal(-1.00000000000000))*(r11)*(x2735)*(x2739)))+(((x2731)*(x2732)))+(((cj7)*(x2731)*(x2733)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2737)))+(((r12)*(sj3)*(x2734)))+(((IkReal(-1.00000000000000))*(x2737)*(x2741)))+(((x2735)*(x2740))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2737)))+(((r22)*(x2734)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2739)))+(((IkReal(-1.00000000000000))*(r11)*(x2736)*(x2739)))+(((cj3)*(sj5)*(x2732)))+(((r12)*(sj7)*(x2736)))+(((x2736)*(x2740)))+(((x2733)*(x2738)))+(((cj5)*(x2741))))))) < IKFAST_ATAN2_MAGTHRESH )
12385  continue;
12386 j4array[0]=IKatan2(((gconst55)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r01)*(x2731)*(x2739)))+(((IkReal(-1.00000000000000))*(r11)*(x2735)*(x2739)))+(((x2731)*(x2732)))+(((cj7)*(x2731)*(x2733)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2737)))+(((r12)*(sj3)*(x2734)))+(((IkReal(-1.00000000000000))*(x2737)*(x2741)))+(((x2735)*(x2740)))))), ((gconst55)*(((((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2737)))+(((r22)*(x2734)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2739)))+(((IkReal(-1.00000000000000))*(r11)*(x2736)*(x2739)))+(((cj3)*(sj5)*(x2732)))+(((r12)*(sj7)*(x2736)))+(((x2736)*(x2740)))+(((x2733)*(x2738)))+(((cj5)*(x2741)))))));
12387 sj4array[0]=IKsin(j4array[0]);
12388 cj4array[0]=IKcos(j4array[0]);
12389 if( j4array[0] > IKPI )
12390 {
12391  j4array[0]-=IK2PI;
12392 }
12393 else if( j4array[0] < -IKPI )
12394 { j4array[0]+=IK2PI;
12395 }
12396 j4valid[0] = true;
12397 for(int ij4 = 0; ij4 < 1; ++ij4)
12398 {
12399 if( !j4valid[ij4] )
12400 {
12401  continue;
12402 }
12403 _ij4[0] = ij4; _ij4[1] = -1;
12404 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12405 {
12406 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12407 {
12408  j4valid[iij4]=false; _ij4[1] = iij4; break;
12409 }
12410 }
12411 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12412 {
12413 IkReal evalcond[4];
12414 IkReal x2742=IKcos(j4);
12415 IkReal x2743=IKsin(j4);
12416 IkReal x2744=((IkReal(1.00000000000000))*(cj7));
12417 IkReal x2745=((cj8)*(r20));
12418 IkReal x2746=((cj3)*(r02));
12419 IkReal x2747=((IkReal(1.00000000000000))*(sj7));
12420 IkReal x2748=((sj3)*(sj7));
12421 IkReal x2749=((r21)*(sj8));
12422 IkReal x2750=((IkReal(1.00000000000000))*(cj5));
12423 IkReal x2751=((cj8)*(r10));
12424 IkReal x2752=((sj5)*(x2743));
12425 IkReal x2753=((sj5)*(x2742));
12426 IkReal x2754=((r11)*(sj3)*(sj8));
12427 IkReal x2755=((cj3)*(cj8)*(r00));
12428 IkReal x2756=((cj3)*(r01)*(sj8));
12429 IkReal x2757=((x2742)*(x2750));
12430 evalcond[0]=((x2752)+(((cj7)*(x2749)))+(((IkReal(-1.00000000000000))*(x2744)*(x2745)))+(((IkReal(-1.00000000000000))*(x2757)))+(((IkReal(-1.00000000000000))*(r22)*(x2747))));
12431 evalcond[1]=((((IkReal(-1.00000000000000))*(x2745)*(x2747)))+(((sj7)*(x2749)))+(((IkReal(-1.00000000000000))*(x2753)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x2743)*(x2750))));
12432 evalcond[2]=((x2753)+(((IkReal(-1.00000000000000))*(x2744)*(x2756)))+(((IkReal(-1.00000000000000))*(x2744)*(x2754)))+(((r12)*(x2748)))+(((cj7)*(x2755)))+(((cj7)*(sj3)*(x2751)))+(((sj7)*(x2746)))+(((cj5)*(x2743))));
12433 evalcond[3]=((x2752)+(((IkReal(-1.00000000000000))*(x2744)*(x2746)))+(((sj7)*(x2755)))+(((x2748)*(x2751)))+(((IkReal(-1.00000000000000))*(x2757)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2744)))+(((IkReal(-1.00000000000000))*(x2747)*(x2756)))+(((IkReal(-1.00000000000000))*(x2747)*(x2754))));
12434 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
12435 {
12436 continue;
12437 }
12438 }
12439 
12440 {
12441 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12442 vinfos[0].jointtype = 1;
12443 vinfos[0].foffset = j3;
12444 vinfos[0].indices[0] = _ij3[0];
12445 vinfos[0].indices[1] = _ij3[1];
12446 vinfos[0].maxsolutions = _nj3;
12447 vinfos[1].jointtype = 1;
12448 vinfos[1].foffset = j4;
12449 vinfos[1].indices[0] = _ij4[0];
12450 vinfos[1].indices[1] = _ij4[1];
12451 vinfos[1].maxsolutions = _nj4;
12452 vinfos[2].jointtype = 1;
12453 vinfos[2].foffset = j5;
12454 vinfos[2].indices[0] = _ij5[0];
12455 vinfos[2].indices[1] = _ij5[1];
12456 vinfos[2].maxsolutions = _nj5;
12457 vinfos[3].jointtype = 1;
12458 vinfos[3].foffset = j6;
12459 vinfos[3].indices[0] = _ij6[0];
12460 vinfos[3].indices[1] = _ij6[1];
12461 vinfos[3].maxsolutions = _nj6;
12462 vinfos[4].jointtype = 1;
12463 vinfos[4].foffset = j7;
12464 vinfos[4].indices[0] = _ij7[0];
12465 vinfos[4].indices[1] = _ij7[1];
12466 vinfos[4].maxsolutions = _nj7;
12467 vinfos[5].jointtype = 1;
12468 vinfos[5].foffset = j8;
12469 vinfos[5].indices[0] = _ij8[0];
12470 vinfos[5].indices[1] = _ij8[1];
12471 vinfos[5].maxsolutions = _nj8;
12472 std::vector<int> vfree(0);
12473 solutions.AddSolution(vinfos,vfree);
12474 }
12475 }
12476 }
12477 
12478 }
12479 
12480 }
12481 
12482 } else
12483 {
12484 {
12485 IkReal j4array[1], cj4array[1], sj4array[1];
12486 bool j4valid[1]={false};
12487 _nj4 = 1;
12488 IkReal x2758=((cj7)*(sj5));
12489 IkReal x2759=((r21)*(sj8));
12490 IkReal x2760=((cj5)*(cj7));
12491 IkReal x2761=((cj8)*(r20));
12492 IkReal x2762=((IkReal(1.00000000000000))*(sj7));
12493 IkReal x2763=((sj5)*(sj7));
12494 if( IKabs(((gconst54)*(((((x2758)*(x2761)))+(((IkReal(-1.00000000000000))*(cj5)*(x2761)*(x2762)))+(((IkReal(-1.00000000000000))*(x2758)*(x2759)))+(((r22)*(x2763)))+(((r22)*(x2760)))+(((cj5)*(sj7)*(x2759))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((r22)*(x2758)))+(((x2759)*(x2763)))+(((x2759)*(x2760)))+(((IkReal(-1.00000000000000))*(sj5)*(x2761)*(x2762)))+(((IkReal(-1.00000000000000))*(x2760)*(x2761)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x2762))))))) < IKFAST_ATAN2_MAGTHRESH )
12495  continue;
12496 j4array[0]=IKatan2(((gconst54)*(((((x2758)*(x2761)))+(((IkReal(-1.00000000000000))*(cj5)*(x2761)*(x2762)))+(((IkReal(-1.00000000000000))*(x2758)*(x2759)))+(((r22)*(x2763)))+(((r22)*(x2760)))+(((cj5)*(sj7)*(x2759)))))), ((gconst54)*(((((r22)*(x2758)))+(((x2759)*(x2763)))+(((x2759)*(x2760)))+(((IkReal(-1.00000000000000))*(sj5)*(x2761)*(x2762)))+(((IkReal(-1.00000000000000))*(x2760)*(x2761)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x2762)))))));
12497 sj4array[0]=IKsin(j4array[0]);
12498 cj4array[0]=IKcos(j4array[0]);
12499 if( j4array[0] > IKPI )
12500 {
12501  j4array[0]-=IK2PI;
12502 }
12503 else if( j4array[0] < -IKPI )
12504 { j4array[0]+=IK2PI;
12505 }
12506 j4valid[0] = true;
12507 for(int ij4 = 0; ij4 < 1; ++ij4)
12508 {
12509 if( !j4valid[ij4] )
12510 {
12511  continue;
12512 }
12513 _ij4[0] = ij4; _ij4[1] = -1;
12514 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12515 {
12516 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12517 {
12518  j4valid[iij4]=false; _ij4[1] = iij4; break;
12519 }
12520 }
12521 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12522 {
12523 IkReal evalcond[4];
12524 IkReal x2764=IKcos(j4);
12525 IkReal x2765=IKsin(j4);
12526 IkReal x2766=((IkReal(1.00000000000000))*(cj7));
12527 IkReal x2767=((cj8)*(r20));
12528 IkReal x2768=((cj3)*(r02));
12529 IkReal x2769=((IkReal(1.00000000000000))*(sj7));
12530 IkReal x2770=((sj3)*(sj7));
12531 IkReal x2771=((r21)*(sj8));
12532 IkReal x2772=((IkReal(1.00000000000000))*(cj5));
12533 IkReal x2773=((cj8)*(r10));
12534 IkReal x2774=((sj5)*(x2765));
12535 IkReal x2775=((sj5)*(x2764));
12536 IkReal x2776=((r11)*(sj3)*(sj8));
12537 IkReal x2777=((cj3)*(cj8)*(r00));
12538 IkReal x2778=((cj3)*(r01)*(sj8));
12539 IkReal x2779=((x2764)*(x2772));
12540 evalcond[0]=((x2774)+(((cj7)*(x2771)))+(((IkReal(-1.00000000000000))*(x2779)))+(((IkReal(-1.00000000000000))*(r22)*(x2769)))+(((IkReal(-1.00000000000000))*(x2766)*(x2767))));
12541 evalcond[1]=((((IkReal(-1.00000000000000))*(x2775)))+(((sj7)*(x2771)))+(((IkReal(-1.00000000000000))*(x2767)*(x2769)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x2765)*(x2772))));
12542 evalcond[2]=((x2775)+(((IkReal(-1.00000000000000))*(x2766)*(x2776)))+(((IkReal(-1.00000000000000))*(x2766)*(x2778)))+(((cj5)*(x2765)))+(((cj7)*(x2777)))+(((sj7)*(x2768)))+(((r12)*(x2770)))+(((cj7)*(sj3)*(x2773))));
12543 evalcond[3]=((x2774)+(((x2770)*(x2773)))+(((sj7)*(x2777)))+(((IkReal(-1.00000000000000))*(x2769)*(x2776)))+(((IkReal(-1.00000000000000))*(x2769)*(x2778)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2766)))+(((IkReal(-1.00000000000000))*(x2779)))+(((IkReal(-1.00000000000000))*(x2766)*(x2768))));
12544 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
12545 {
12546 continue;
12547 }
12548 }
12549 
12550 {
12551 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12552 vinfos[0].jointtype = 1;
12553 vinfos[0].foffset = j3;
12554 vinfos[0].indices[0] = _ij3[0];
12555 vinfos[0].indices[1] = _ij3[1];
12556 vinfos[0].maxsolutions = _nj3;
12557 vinfos[1].jointtype = 1;
12558 vinfos[1].foffset = j4;
12559 vinfos[1].indices[0] = _ij4[0];
12560 vinfos[1].indices[1] = _ij4[1];
12561 vinfos[1].maxsolutions = _nj4;
12562 vinfos[2].jointtype = 1;
12563 vinfos[2].foffset = j5;
12564 vinfos[2].indices[0] = _ij5[0];
12565 vinfos[2].indices[1] = _ij5[1];
12566 vinfos[2].maxsolutions = _nj5;
12567 vinfos[3].jointtype = 1;
12568 vinfos[3].foffset = j6;
12569 vinfos[3].indices[0] = _ij6[0];
12570 vinfos[3].indices[1] = _ij6[1];
12571 vinfos[3].maxsolutions = _nj6;
12572 vinfos[4].jointtype = 1;
12573 vinfos[4].foffset = j7;
12574 vinfos[4].indices[0] = _ij7[0];
12575 vinfos[4].indices[1] = _ij7[1];
12576 vinfos[4].maxsolutions = _nj7;
12577 vinfos[5].jointtype = 1;
12578 vinfos[5].foffset = j8;
12579 vinfos[5].indices[0] = _ij8[0];
12580 vinfos[5].indices[1] = _ij8[1];
12581 vinfos[5].maxsolutions = _nj8;
12582 std::vector<int> vfree(0);
12583 solutions.AddSolution(vinfos,vfree);
12584 }
12585 }
12586 }
12587 
12588 }
12589 
12590 }
12591 
12592 } else
12593 {
12594 if( 1 )
12595 {
12596 continue;
12597 
12598 } else
12599 {
12600 }
12601 }
12602 }
12603 }
12604 }
12605 }
12606 
12607 } else
12608 {
12609 {
12610 IkReal j4array[1], cj4array[1], sj4array[1];
12611 bool j4valid[1]={false};
12612 _nj4 = 1;
12613 IkReal x2780=((r21)*(sj8));
12614 IkReal x2781=((IkReal(1.00000000000000))*(r22));
12615 IkReal x2782=((cj5)*(sj7));
12616 IkReal x2783=((cj6)*(cj7));
12617 IkReal x2784=((sj5)*(sj7));
12618 IkReal x2785=((cj5)*(cj8)*(r20));
12619 IkReal x2786=((IkReal(1.00000000000000))*(x2783));
12620 IkReal x2787=((cj8)*(r20)*(sj5));
12621 if( IKabs(((gconst47)*(((((cj6)*(r22)*(x2784)))+(((x2783)*(x2787)))+(((cj8)*(r20)*(x2782)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x2781)))+(((IkReal(-1.00000000000000))*(sj5)*(x2780)*(x2786)))+(((IkReal(-1.00000000000000))*(x2780)*(x2782))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x2781)))+(((IkReal(-1.00000000000000))*(x2785)*(x2786)))+(((cj8)*(r20)*(x2784)))+(((cj5)*(x2780)*(x2783)))+(((IkReal(-1.00000000000000))*(cj6)*(x2781)*(x2782)))+(((IkReal(-1.00000000000000))*(x2780)*(x2784))))))) < IKFAST_ATAN2_MAGTHRESH )
12622  continue;
12623 j4array[0]=IKatan2(((gconst47)*(((((cj6)*(r22)*(x2784)))+(((x2783)*(x2787)))+(((cj8)*(r20)*(x2782)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x2781)))+(((IkReal(-1.00000000000000))*(sj5)*(x2780)*(x2786)))+(((IkReal(-1.00000000000000))*(x2780)*(x2782)))))), ((gconst47)*(((((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x2781)))+(((IkReal(-1.00000000000000))*(x2785)*(x2786)))+(((cj8)*(r20)*(x2784)))+(((cj5)*(x2780)*(x2783)))+(((IkReal(-1.00000000000000))*(cj6)*(x2781)*(x2782)))+(((IkReal(-1.00000000000000))*(x2780)*(x2784)))))));
12624 sj4array[0]=IKsin(j4array[0]);
12625 cj4array[0]=IKcos(j4array[0]);
12626 if( j4array[0] > IKPI )
12627 {
12628  j4array[0]-=IK2PI;
12629 }
12630 else if( j4array[0] < -IKPI )
12631 { j4array[0]+=IK2PI;
12632 }
12633 j4valid[0] = true;
12634 for(int ij4 = 0; ij4 < 1; ++ij4)
12635 {
12636 if( !j4valid[ij4] )
12637 {
12638  continue;
12639 }
12640 _ij4[0] = ij4; _ij4[1] = -1;
12641 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12642 {
12643 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12644 {
12645  j4valid[iij4]=false; _ij4[1] = iij4; break;
12646 }
12647 }
12648 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12649 {
12650 IkReal evalcond[6];
12651 IkReal x2788=IKsin(j4);
12652 IkReal x2789=IKcos(j4);
12653 IkReal x2790=((IkReal(1.00000000000000))*(cj8));
12654 IkReal x2791=((cj3)*(r01));
12655 IkReal x2792=((IkReal(1.00000000000000))*(sj8));
12656 IkReal x2793=((r11)*(sj3));
12657 IkReal x2794=((cj3)*(r00));
12658 IkReal x2795=((IkReal(1.00000000000000))*(sj6));
12659 IkReal x2796=((IkReal(1.00000000000000))*(cj7));
12660 IkReal x2797=((cj3)*(r02));
12661 IkReal x2798=((sj3)*(sj7));
12662 IkReal x2799=((cj7)*(cj8));
12663 IkReal x2800=((r21)*(sj8));
12664 IkReal x2801=((r10)*(sj3));
12665 IkReal x2802=((sj5)*(x2789));
12666 IkReal x2803=((cj5)*(x2789));
12667 IkReal x2804=((cj6)*(x2788));
12668 IkReal x2805=((cj5)*(x2788));
12669 IkReal x2806=((sj5)*(x2788));
12670 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2795)*(x2805)))+(((IkReal(-1.00000000000000))*(x2795)*(x2802)))+(((r20)*(sj8))));
12671 evalcond[1]=((((IkReal(-1.00000000000000))*(x2803)))+(((cj7)*(x2800)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x2806)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2790))));
12672 evalcond[2]=((((cj6)*(x2802)))+(((cj5)*(x2804)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(sj7)*(x2790)))+(((sj7)*(x2800))));
12673 evalcond[3]=((((IkReal(-1.00000000000000))*(x2790)*(x2793)))+(((IkReal(-1.00000000000000))*(x2790)*(x2791)))+(((IkReal(-1.00000000000000))*(x2795)*(x2803)))+(((IkReal(-1.00000000000000))*(x2792)*(x2801)))+(((IkReal(-1.00000000000000))*(x2792)*(x2794)))+(((sj6)*(x2806))));
12674 evalcond[4]=((((IkReal(-1.00000000000000))*(cj7)*(x2792)*(x2793)))+(((x2794)*(x2799)))+(((IkReal(-1.00000000000000))*(cj7)*(x2791)*(x2792)))+(((sj7)*(x2797)))+(((r12)*(x2798)))+(((x2799)*(x2801)))+(x2802)+(x2805));
12675 evalcond[5]=((((cj6)*(x2803)))+(((IkReal(-1.00000000000000))*(x2796)*(x2797)))+(((cj8)*(sj7)*(x2794)))+(((IkReal(-1.00000000000000))*(sj7)*(x2791)*(x2792)))+(((IkReal(-1.00000000000000))*(sj5)*(x2804)))+(((cj8)*(r10)*(x2798)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2796)))+(((IkReal(-1.00000000000000))*(sj7)*(x2792)*(x2793))));
12676 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
12677 {
12678 continue;
12679 }
12680 }
12681 
12682 {
12683 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12684 vinfos[0].jointtype = 1;
12685 vinfos[0].foffset = j3;
12686 vinfos[0].indices[0] = _ij3[0];
12687 vinfos[0].indices[1] = _ij3[1];
12688 vinfos[0].maxsolutions = _nj3;
12689 vinfos[1].jointtype = 1;
12690 vinfos[1].foffset = j4;
12691 vinfos[1].indices[0] = _ij4[0];
12692 vinfos[1].indices[1] = _ij4[1];
12693 vinfos[1].maxsolutions = _nj4;
12694 vinfos[2].jointtype = 1;
12695 vinfos[2].foffset = j5;
12696 vinfos[2].indices[0] = _ij5[0];
12697 vinfos[2].indices[1] = _ij5[1];
12698 vinfos[2].maxsolutions = _nj5;
12699 vinfos[3].jointtype = 1;
12700 vinfos[3].foffset = j6;
12701 vinfos[3].indices[0] = _ij6[0];
12702 vinfos[3].indices[1] = _ij6[1];
12703 vinfos[3].maxsolutions = _nj6;
12704 vinfos[4].jointtype = 1;
12705 vinfos[4].foffset = j7;
12706 vinfos[4].indices[0] = _ij7[0];
12707 vinfos[4].indices[1] = _ij7[1];
12708 vinfos[4].maxsolutions = _nj7;
12709 vinfos[5].jointtype = 1;
12710 vinfos[5].foffset = j8;
12711 vinfos[5].indices[0] = _ij8[0];
12712 vinfos[5].indices[1] = _ij8[1];
12713 vinfos[5].maxsolutions = _nj8;
12714 std::vector<int> vfree(0);
12715 solutions.AddSolution(vinfos,vfree);
12716 }
12717 }
12718 }
12719 
12720 }
12721 
12722 }
12723 
12724 } else
12725 {
12726 {
12727 IkReal j4array[1], cj4array[1], sj4array[1];
12728 bool j4valid[1]={false};
12729 _nj4 = 1;
12730 IkReal x2807=((sj5)*(sj6));
12731 IkReal x2808=((r22)*(sj7));
12732 IkReal x2809=((r20)*(sj8));
12733 IkReal x2810=((cj8)*(r21));
12734 IkReal x2811=((cj5)*(sj6));
12735 IkReal x2812=((cj7)*(cj8)*(r20));
12736 IkReal x2813=((cj7)*(r21)*(sj8));
12737 if( IKabs(((gconst46)*(((((cj5)*(x2810)))+(((cj5)*(x2809)))+(((IkReal(-1.00000000000000))*(x2807)*(x2813)))+(((x2807)*(x2808)))+(((x2807)*(x2812))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(x2808)*(x2811)))+(((IkReal(-1.00000000000000))*(x2811)*(x2812)))+(((sj5)*(x2809)))+(((sj5)*(x2810)))+(((x2811)*(x2813))))))) < IKFAST_ATAN2_MAGTHRESH )
12738  continue;
12739 j4array[0]=IKatan2(((gconst46)*(((((cj5)*(x2810)))+(((cj5)*(x2809)))+(((IkReal(-1.00000000000000))*(x2807)*(x2813)))+(((x2807)*(x2808)))+(((x2807)*(x2812)))))), ((gconst46)*(((((IkReal(-1.00000000000000))*(x2808)*(x2811)))+(((IkReal(-1.00000000000000))*(x2811)*(x2812)))+(((sj5)*(x2809)))+(((sj5)*(x2810)))+(((x2811)*(x2813)))))));
12740 sj4array[0]=IKsin(j4array[0]);
12741 cj4array[0]=IKcos(j4array[0]);
12742 if( j4array[0] > IKPI )
12743 {
12744  j4array[0]-=IK2PI;
12745 }
12746 else if( j4array[0] < -IKPI )
12747 { j4array[0]+=IK2PI;
12748 }
12749 j4valid[0] = true;
12750 for(int ij4 = 0; ij4 < 1; ++ij4)
12751 {
12752 if( !j4valid[ij4] )
12753 {
12754  continue;
12755 }
12756 _ij4[0] = ij4; _ij4[1] = -1;
12757 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12758 {
12759 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12760 {
12761  j4valid[iij4]=false; _ij4[1] = iij4; break;
12762 }
12763 }
12764 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12765 {
12766 IkReal evalcond[6];
12767 IkReal x2814=IKsin(j4);
12768 IkReal x2815=IKcos(j4);
12769 IkReal x2816=((IkReal(1.00000000000000))*(cj8));
12770 IkReal x2817=((cj3)*(r01));
12771 IkReal x2818=((IkReal(1.00000000000000))*(sj8));
12772 IkReal x2819=((r11)*(sj3));
12773 IkReal x2820=((cj3)*(r00));
12774 IkReal x2821=((IkReal(1.00000000000000))*(sj6));
12775 IkReal x2822=((IkReal(1.00000000000000))*(cj7));
12776 IkReal x2823=((cj3)*(r02));
12777 IkReal x2824=((sj3)*(sj7));
12778 IkReal x2825=((cj7)*(cj8));
12779 IkReal x2826=((r21)*(sj8));
12780 IkReal x2827=((r10)*(sj3));
12781 IkReal x2828=((sj5)*(x2815));
12782 IkReal x2829=((cj5)*(x2815));
12783 IkReal x2830=((cj6)*(x2814));
12784 IkReal x2831=((cj5)*(x2814));
12785 IkReal x2832=((sj5)*(x2814));
12786 evalcond[0]=((((IkReal(-1.00000000000000))*(x2821)*(x2828)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2821)*(x2831)))+(((r20)*(sj8))));
12787 evalcond[1]=((((IkReal(-1.00000000000000))*(x2829)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2816)))+(x2832)+(((cj7)*(x2826))));
12788 evalcond[2]=((((cj6)*(x2828)))+(((cj5)*(x2830)))+(((IkReal(-1.00000000000000))*(r20)*(sj7)*(x2816)))+(((sj7)*(x2826)))+(((cj7)*(r22))));
12789 evalcond[3]=((((IkReal(-1.00000000000000))*(x2821)*(x2829)))+(((IkReal(-1.00000000000000))*(x2818)*(x2827)))+(((IkReal(-1.00000000000000))*(x2818)*(x2820)))+(((IkReal(-1.00000000000000))*(x2816)*(x2817)))+(((IkReal(-1.00000000000000))*(x2816)*(x2819)))+(((sj6)*(x2832))));
12790 evalcond[4]=((((sj7)*(x2823)))+(((IkReal(-1.00000000000000))*(cj7)*(x2817)*(x2818)))+(((x2825)*(x2827)))+(((IkReal(-1.00000000000000))*(cj7)*(x2818)*(x2819)))+(x2831)+(x2828)+(((x2820)*(x2825)))+(((r12)*(x2824))));
12791 evalcond[5]=((((IkReal(-1.00000000000000))*(sj7)*(x2818)*(x2819)))+(((cj6)*(x2829)))+(((IkReal(-1.00000000000000))*(x2822)*(x2823)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2822)))+(((cj8)*(r10)*(x2824)))+(((IkReal(-1.00000000000000))*(sj5)*(x2830)))+(((IkReal(-1.00000000000000))*(sj7)*(x2817)*(x2818)))+(((cj8)*(sj7)*(x2820))));
12792 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
12793 {
12794 continue;
12795 }
12796 }
12797 
12798 {
12799 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12800 vinfos[0].jointtype = 1;
12801 vinfos[0].foffset = j3;
12802 vinfos[0].indices[0] = _ij3[0];
12803 vinfos[0].indices[1] = _ij3[1];
12804 vinfos[0].maxsolutions = _nj3;
12805 vinfos[1].jointtype = 1;
12806 vinfos[1].foffset = j4;
12807 vinfos[1].indices[0] = _ij4[0];
12808 vinfos[1].indices[1] = _ij4[1];
12809 vinfos[1].maxsolutions = _nj4;
12810 vinfos[2].jointtype = 1;
12811 vinfos[2].foffset = j5;
12812 vinfos[2].indices[0] = _ij5[0];
12813 vinfos[2].indices[1] = _ij5[1];
12814 vinfos[2].maxsolutions = _nj5;
12815 vinfos[3].jointtype = 1;
12816 vinfos[3].foffset = j6;
12817 vinfos[3].indices[0] = _ij6[0];
12818 vinfos[3].indices[1] = _ij6[1];
12819 vinfos[3].maxsolutions = _nj6;
12820 vinfos[4].jointtype = 1;
12821 vinfos[4].foffset = j7;
12822 vinfos[4].indices[0] = _ij7[0];
12823 vinfos[4].indices[1] = _ij7[1];
12824 vinfos[4].maxsolutions = _nj7;
12825 vinfos[5].jointtype = 1;
12826 vinfos[5].foffset = j8;
12827 vinfos[5].indices[0] = _ij8[0];
12828 vinfos[5].indices[1] = _ij8[1];
12829 vinfos[5].maxsolutions = _nj8;
12830 std::vector<int> vfree(0);
12831 solutions.AddSolution(vinfos,vfree);
12832 }
12833 }
12834 }
12835 
12836 }
12837 
12838 }
12839 }
12840 }
12841 
12842 }
12843 
12844 }
12845 }
12846 }
12847 
12848 }
12849 
12850 }
12851 
12852 } else
12853 {
12854 {
12855 IkReal j3array[1], cj3array[1], sj3array[1];
12856 bool j3valid[1]={false};
12857 _nj3 = 1;
12858 IkReal x2833=((cj6)*(sj7));
12859 IkReal x2834=((cj6)*(cj7));
12860 IkReal x2835=((IkReal(1.00000000000000))*(sj8));
12861 if( IKabs(((gconst0)*(((((r12)*(x2833)))+(((cj8)*(r10)*(x2834)))+(((IkReal(-1.00000000000000))*(r11)*(x2834)*(x2835))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((IkReal(-1.00000000000000))*(r01)*(x2834)*(x2835)))+(((r02)*(x2833)))+(((cj8)*(r00)*(x2834))))))) < IKFAST_ATAN2_MAGTHRESH )
12862  continue;
12863 j3array[0]=IKatan2(((gconst0)*(((((r12)*(x2833)))+(((cj8)*(r10)*(x2834)))+(((IkReal(-1.00000000000000))*(r11)*(x2834)*(x2835)))))), ((gconst0)*(((((IkReal(-1.00000000000000))*(r01)*(x2834)*(x2835)))+(((r02)*(x2833)))+(((cj8)*(r00)*(x2834)))))));
12864 sj3array[0]=IKsin(j3array[0]);
12865 cj3array[0]=IKcos(j3array[0]);
12866 if( j3array[0] > IKPI )
12867 {
12868  j3array[0]-=IK2PI;
12869 }
12870 else if( j3array[0] < -IKPI )
12871 { j3array[0]+=IK2PI;
12872 }
12873 j3valid[0] = true;
12874 for(int ij3 = 0; ij3 < 1; ++ij3)
12875 {
12876 if( !j3valid[ij3] )
12877 {
12878  continue;
12879 }
12880 _ij3[0] = ij3; _ij3[1] = -1;
12881 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12882 {
12883 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12884 {
12885  j3valid[iij3]=false; _ij3[1] = iij3; break;
12886 }
12887 }
12888 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12889 {
12890 IkReal evalcond[3];
12891 IkReal x2836=IKsin(j3);
12892 IkReal x2837=IKcos(j3);
12893 IkReal x2838=((IkReal(1.00000000000000))*(r11));
12894 IkReal x2839=((r01)*(sj8));
12895 IkReal x2840=((cj8)*(r10));
12896 IkReal x2841=((IkReal(1.00000000000000))*(sj7));
12897 IkReal x2842=((sj7)*(x2837));
12898 IkReal x2843=((cj7)*(x2836));
12899 IkReal x2844=((r00)*(x2836));
12900 IkReal x2845=((cj7)*(x2837));
12901 evalcond[0]=((((sj8)*(x2844)))+(cj6)+(((IkReal(-1.00000000000000))*(cj8)*(x2837)*(x2838)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2837)))+(((cj8)*(r01)*(x2836))));
12902 evalcond[1]=((((IkReal(-1.00000000000000))*(sj8)*(x2838)*(x2845)))+(((r12)*(x2842)))+(((IkReal(-1.00000000000000))*(r02)*(x2836)*(x2841)))+(((x2840)*(x2845)))+(((IkReal(-1.00000000000000))*(cj8)*(r00)*(x2843)))+(((x2839)*(x2843))));
12903 evalcond[2]=((((IkReal(-1.00000000000000))*(sj8)*(x2838)*(x2842)))+(sj6)+(((IkReal(-1.00000000000000))*(r12)*(x2845)))+(((x2840)*(x2842)))+(((IkReal(-1.00000000000000))*(cj8)*(x2841)*(x2844)))+(((sj7)*(x2836)*(x2839)))+(((r02)*(x2843))));
12904 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
12905 {
12906 continue;
12907 }
12908 }
12909 
12910 {
12911 IkReal dummyeval[1];
12912 dummyeval[0]=sj6;
12913 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12914 {
12915 {
12916 IkReal dummyeval[1];
12917 dummyeval[0]=cj6;
12918 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12919 {
12920 {
12921 IkReal evalcond[7];
12922 IkReal x2846=((IkReal(1.00000000000000))*(cj3));
12923 IkReal x2847=((cj7)*(r02));
12924 IkReal x2848=((cj8)*(sj7));
12925 IkReal x2849=((r01)*(sj3));
12926 IkReal x2850=((IkReal(1.00000000000000))*(sj3));
12927 IkReal x2851=((sj7)*(sj8));
12928 IkReal x2852=((cj7)*(r12));
12929 IkReal x2853=((cj7)*(cj8));
12930 IkReal x2854=((cj3)*(r10));
12931 IkReal x2855=((cj7)*(sj8));
12932 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
12933 evalcond[1]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2846)))+(((r00)*(sj3)*(sj8)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2846)))+(((cj8)*(x2849))));
12934 evalcond[2]=((((r21)*(x2851)))+(((IkReal(-1.00000000000000))*(r20)*(x2848)))+(((cj7)*(r22))));
12935 evalcond[3]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x2851)))+(((IkReal(-1.00000000000000))*(npx)*(x2848)))+(((cj7)*(npz))));
12936 evalcond[4]=((((cj3)*(r12)*(sj7)))+(((IkReal(-1.00000000000000))*(r00)*(x2850)*(x2853)))+(((x2849)*(x2855)))+(((x2853)*(x2854)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x2850)))+(((IkReal(-1.00000000000000))*(r11)*(x2846)*(x2855))));
12937 evalcond[5]=((IkReal(1.00000000000000))+(((x2849)*(x2851)))+(((sj3)*(x2847)))+(((x2848)*(x2854)))+(((IkReal(-1.00000000000000))*(r00)*(x2848)*(x2850)))+(((IkReal(-1.00000000000000))*(r11)*(x2846)*(x2851)))+(((IkReal(-1.00000000000000))*(x2846)*(x2852))));
12938 evalcond[6]=((((IkReal(-1.00000000000000))*(x2846)*(x2847)))+(((r10)*(sj3)*(x2848)))+(((IkReal(-1.00000000000000))*(r01)*(x2846)*(x2851)))+(((IkReal(-1.00000000000000))*(x2850)*(x2852)))+(((IkReal(-1.00000000000000))*(r11)*(x2850)*(x2851)))+(((cj3)*(r00)*(x2848))));
12939 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
12940 {
12941 {
12942 IkReal j5array[1], cj5array[1], sj5array[1];
12943 bool j5valid[1]={false};
12944 _nj5 = 1;
12945 IkReal x2856=((IkReal(4.00000000000000))*(npx));
12946 IkReal x2857=((IkReal(4.00000000000000))*(npy));
12947 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(sj8)*(x2856)))+(((IkReal(-1.00000000000000))*(cj8)*(x2857))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2857)))+(((cj7)*(cj8)*(x2856)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(sj8)*(x2856)))+(((IkReal(-1.00000000000000))*(cj8)*(x2857)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2857)))+(((cj7)*(cj8)*(x2856)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
12948  continue;
12949 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(sj8)*(x2856)))+(((IkReal(-1.00000000000000))*(cj8)*(x2857)))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2857)))+(((cj7)*(cj8)*(x2856)))+(((IkReal(-0.360000000000000))*(cj7)))));
12950 sj5array[0]=IKsin(j5array[0]);
12951 cj5array[0]=IKcos(j5array[0]);
12952 if( j5array[0] > IKPI )
12953 {
12954  j5array[0]-=IK2PI;
12955 }
12956 else if( j5array[0] < -IKPI )
12957 { j5array[0]+=IK2PI;
12958 }
12959 j5valid[0] = true;
12960 for(int ij5 = 0; ij5 < 1; ++ij5)
12961 {
12962 if( !j5valid[ij5] )
12963 {
12964  continue;
12965 }
12966 _ij5[0] = ij5; _ij5[1] = -1;
12967 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12968 {
12969 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12970 {
12971  j5valid[iij5]=false; _ij5[1] = iij5; break;
12972 }
12973 }
12974 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12975 {
12976 IkReal evalcond[2];
12977 evalcond[0]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(IKsin(j5)))));
12978 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(cj8)*(npx)))+(((cj7)*(npy)*(sj8)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
12979 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
12980 {
12981 continue;
12982 }
12983 }
12984 
12985 {
12986 IkReal dummyeval[1];
12987 IkReal gconst56;
12988 gconst56=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
12989 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
12990 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12991 {
12992 {
12993 IkReal dummyeval[1];
12994 IkReal gconst57;
12995 gconst57=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
12996 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
12997 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
12998 {
12999 continue;
13000 
13001 } else
13002 {
13003 {
13004 IkReal j4array[1], cj4array[1], sj4array[1];
13005 bool j4valid[1]={false};
13006 _nj4 = 1;
13007 IkReal x2858=((cj8)*(sj5));
13008 IkReal x2859=((cj3)*(r01));
13009 IkReal x2860=((IkReal(1.00000000000000))*(cj5));
13010 IkReal x2861=((r11)*(sj3));
13011 IkReal x2862=((sj5)*(sj8));
13012 IkReal x2863=((r10)*(sj3));
13013 IkReal x2864=((cj3)*(r00)*(sj8));
13014 if( IKabs(((gconst57)*(((((x2858)*(x2859)))+(((cj5)*(r20)*(sj8)))+(((x2858)*(x2861)))+(((cj3)*(r00)*(x2862)))+(((x2862)*(x2863)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst57)*(((((r21)*(x2858)))+(((IkReal(-1.00000000000000))*(cj8)*(x2859)*(x2860)))+(((IkReal(-1.00000000000000))*(x2860)*(x2864)))+(((IkReal(-1.00000000000000))*(cj8)*(x2860)*(x2861)))+(((r20)*(x2862)))+(((IkReal(-1.00000000000000))*(sj8)*(x2860)*(x2863))))))) < IKFAST_ATAN2_MAGTHRESH )
13015  continue;
13016 j4array[0]=IKatan2(((gconst57)*(((((x2858)*(x2859)))+(((cj5)*(r20)*(sj8)))+(((x2858)*(x2861)))+(((cj3)*(r00)*(x2862)))+(((x2862)*(x2863)))+(((cj5)*(cj8)*(r21)))))), ((gconst57)*(((((r21)*(x2858)))+(((IkReal(-1.00000000000000))*(cj8)*(x2859)*(x2860)))+(((IkReal(-1.00000000000000))*(x2860)*(x2864)))+(((IkReal(-1.00000000000000))*(cj8)*(x2860)*(x2861)))+(((r20)*(x2862)))+(((IkReal(-1.00000000000000))*(sj8)*(x2860)*(x2863)))))));
13017 sj4array[0]=IKsin(j4array[0]);
13018 cj4array[0]=IKcos(j4array[0]);
13019 if( j4array[0] > IKPI )
13020 {
13021  j4array[0]-=IK2PI;
13022 }
13023 else if( j4array[0] < -IKPI )
13024 { j4array[0]+=IK2PI;
13025 }
13026 j4valid[0] = true;
13027 for(int ij4 = 0; ij4 < 1; ++ij4)
13028 {
13029 if( !j4valid[ij4] )
13030 {
13031  continue;
13032 }
13033 _ij4[0] = ij4; _ij4[1] = -1;
13034 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13035 {
13036 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13037 {
13038  j4valid[iij4]=false; _ij4[1] = iij4; break;
13039 }
13040 }
13041 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13042 {
13043 IkReal evalcond[4];
13044 IkReal x2865=IKsin(j4);
13045 IkReal x2866=IKcos(j4);
13046 IkReal x2867=((IkReal(1.00000000000000))*(cj8));
13047 IkReal x2868=((cj3)*(r01));
13048 IkReal x2869=((cj3)*(r00));
13049 IkReal x2870=((cj7)*(cj8));
13050 IkReal x2871=((IkReal(1.00000000000000))*(cj5));
13051 IkReal x2872=((IkReal(1.00000000000000))*(sj8));
13052 IkReal x2873=((r11)*(sj3));
13053 IkReal x2874=((r10)*(sj3));
13054 IkReal x2875=((sj5)*(x2865));
13055 IkReal x2876=((sj5)*(x2866));
13056 IkReal x2877=((x2866)*(x2871));
13057 evalcond[0]=((((IkReal(-1.00000000000000))*(x2865)*(x2871)))+(((IkReal(-1.00000000000000))*(x2876)))+(((cj8)*(r21)))+(((r20)*(sj8))));
13058 evalcond[1]=((((IkReal(-1.00000000000000))*(x2877)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2867)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x2875)+(((cj7)*(r21)*(sj8))));
13059 evalcond[2]=((((IkReal(-1.00000000000000))*(x2877)))+(((IkReal(-1.00000000000000))*(x2869)*(x2872)))+(((IkReal(-1.00000000000000))*(x2872)*(x2874)))+(((IkReal(-1.00000000000000))*(x2867)*(x2868)))+(((IkReal(-1.00000000000000))*(x2867)*(x2873)))+(x2875));
13060 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2868)*(x2872)))+(((x2870)*(x2874)))+(((cj5)*(x2865)))+(((x2869)*(x2870)))+(((IkReal(-1.00000000000000))*(cj7)*(x2872)*(x2873)))+(((cj3)*(r02)*(sj7)))+(x2876));
13061 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
13062 {
13063 continue;
13064 }
13065 }
13066 
13067 {
13068 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13069 vinfos[0].jointtype = 1;
13070 vinfos[0].foffset = j3;
13071 vinfos[0].indices[0] = _ij3[0];
13072 vinfos[0].indices[1] = _ij3[1];
13073 vinfos[0].maxsolutions = _nj3;
13074 vinfos[1].jointtype = 1;
13075 vinfos[1].foffset = j4;
13076 vinfos[1].indices[0] = _ij4[0];
13077 vinfos[1].indices[1] = _ij4[1];
13078 vinfos[1].maxsolutions = _nj4;
13079 vinfos[2].jointtype = 1;
13080 vinfos[2].foffset = j5;
13081 vinfos[2].indices[0] = _ij5[0];
13082 vinfos[2].indices[1] = _ij5[1];
13083 vinfos[2].maxsolutions = _nj5;
13084 vinfos[3].jointtype = 1;
13085 vinfos[3].foffset = j6;
13086 vinfos[3].indices[0] = _ij6[0];
13087 vinfos[3].indices[1] = _ij6[1];
13088 vinfos[3].maxsolutions = _nj6;
13089 vinfos[4].jointtype = 1;
13090 vinfos[4].foffset = j7;
13091 vinfos[4].indices[0] = _ij7[0];
13092 vinfos[4].indices[1] = _ij7[1];
13093 vinfos[4].maxsolutions = _nj7;
13094 vinfos[5].jointtype = 1;
13095 vinfos[5].foffset = j8;
13096 vinfos[5].indices[0] = _ij8[0];
13097 vinfos[5].indices[1] = _ij8[1];
13098 vinfos[5].maxsolutions = _nj8;
13099 std::vector<int> vfree(0);
13100 solutions.AddSolution(vinfos,vfree);
13101 }
13102 }
13103 }
13104 
13105 }
13106 
13107 }
13108 
13109 } else
13110 {
13111 {
13112 IkReal j4array[1], cj4array[1], sj4array[1];
13113 bool j4valid[1]={false};
13114 _nj4 = 1;
13115 IkReal x2878=((cj7)*(sj5));
13116 IkReal x2879=((r21)*(sj8));
13117 IkReal x2880=((cj8)*(r20));
13118 IkReal x2881=((cj5)*(cj7));
13119 IkReal x2882=((r22)*(sj7));
13120 IkReal x2883=((cj8)*(r21));
13121 IkReal x2884=((r20)*(sj8));
13122 if( IKabs(((gconst56)*(((((IkReal(-1.00000000000000))*(x2878)*(x2879)))+(((sj5)*(x2882)))+(((x2878)*(x2880)))+(((cj5)*(x2883)))+(((cj5)*(x2884))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst56)*(((((sj5)*(x2883)))+(((sj5)*(x2884)))+(((IkReal(-1.00000000000000))*(x2880)*(x2881)))+(((x2879)*(x2881)))+(((IkReal(-1.00000000000000))*(cj5)*(x2882))))))) < IKFAST_ATAN2_MAGTHRESH )
13123  continue;
13124 j4array[0]=IKatan2(((gconst56)*(((((IkReal(-1.00000000000000))*(x2878)*(x2879)))+(((sj5)*(x2882)))+(((x2878)*(x2880)))+(((cj5)*(x2883)))+(((cj5)*(x2884)))))), ((gconst56)*(((((sj5)*(x2883)))+(((sj5)*(x2884)))+(((IkReal(-1.00000000000000))*(x2880)*(x2881)))+(((x2879)*(x2881)))+(((IkReal(-1.00000000000000))*(cj5)*(x2882)))))));
13125 sj4array[0]=IKsin(j4array[0]);
13126 cj4array[0]=IKcos(j4array[0]);
13127 if( j4array[0] > IKPI )
13128 {
13129  j4array[0]-=IK2PI;
13130 }
13131 else if( j4array[0] < -IKPI )
13132 { j4array[0]+=IK2PI;
13133 }
13134 j4valid[0] = true;
13135 for(int ij4 = 0; ij4 < 1; ++ij4)
13136 {
13137 if( !j4valid[ij4] )
13138 {
13139  continue;
13140 }
13141 _ij4[0] = ij4; _ij4[1] = -1;
13142 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13143 {
13144 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13145 {
13146  j4valid[iij4]=false; _ij4[1] = iij4; break;
13147 }
13148 }
13149 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13150 {
13151 IkReal evalcond[4];
13152 IkReal x2885=IKsin(j4);
13153 IkReal x2886=IKcos(j4);
13154 IkReal x2887=((IkReal(1.00000000000000))*(cj8));
13155 IkReal x2888=((cj3)*(r01));
13156 IkReal x2889=((cj3)*(r00));
13157 IkReal x2890=((cj7)*(cj8));
13158 IkReal x2891=((IkReal(1.00000000000000))*(cj5));
13159 IkReal x2892=((IkReal(1.00000000000000))*(sj8));
13160 IkReal x2893=((r11)*(sj3));
13161 IkReal x2894=((r10)*(sj3));
13162 IkReal x2895=((sj5)*(x2885));
13163 IkReal x2896=((sj5)*(x2886));
13164 IkReal x2897=((x2886)*(x2891));
13165 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x2896)))+(((IkReal(-1.00000000000000))*(x2885)*(x2891)))+(((r20)*(sj8))));
13166 evalcond[1]=((((IkReal(-1.00000000000000))*(x2897)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2887)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(x2895)+(((cj7)*(r21)*(sj8))));
13167 evalcond[2]=((((IkReal(-1.00000000000000))*(x2887)*(x2888)))+(((IkReal(-1.00000000000000))*(x2889)*(x2892)))+(((IkReal(-1.00000000000000))*(x2887)*(x2893)))+(((IkReal(-1.00000000000000))*(x2892)*(x2894)))+(((IkReal(-1.00000000000000))*(x2897)))+(x2895));
13168 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x2890)*(x2894)))+(((x2889)*(x2890)))+(((IkReal(-1.00000000000000))*(cj7)*(x2888)*(x2892)))+(((IkReal(-1.00000000000000))*(cj7)*(x2892)*(x2893)))+(((cj3)*(r02)*(sj7)))+(((cj5)*(x2885)))+(x2896));
13169 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
13170 {
13171 continue;
13172 }
13173 }
13174 
13175 {
13176 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13177 vinfos[0].jointtype = 1;
13178 vinfos[0].foffset = j3;
13179 vinfos[0].indices[0] = _ij3[0];
13180 vinfos[0].indices[1] = _ij3[1];
13181 vinfos[0].maxsolutions = _nj3;
13182 vinfos[1].jointtype = 1;
13183 vinfos[1].foffset = j4;
13184 vinfos[1].indices[0] = _ij4[0];
13185 vinfos[1].indices[1] = _ij4[1];
13186 vinfos[1].maxsolutions = _nj4;
13187 vinfos[2].jointtype = 1;
13188 vinfos[2].foffset = j5;
13189 vinfos[2].indices[0] = _ij5[0];
13190 vinfos[2].indices[1] = _ij5[1];
13191 vinfos[2].maxsolutions = _nj5;
13192 vinfos[3].jointtype = 1;
13193 vinfos[3].foffset = j6;
13194 vinfos[3].indices[0] = _ij6[0];
13195 vinfos[3].indices[1] = _ij6[1];
13196 vinfos[3].maxsolutions = _nj6;
13197 vinfos[4].jointtype = 1;
13198 vinfos[4].foffset = j7;
13199 vinfos[4].indices[0] = _ij7[0];
13200 vinfos[4].indices[1] = _ij7[1];
13201 vinfos[4].maxsolutions = _nj7;
13202 vinfos[5].jointtype = 1;
13203 vinfos[5].foffset = j8;
13204 vinfos[5].indices[0] = _ij8[0];
13205 vinfos[5].indices[1] = _ij8[1];
13206 vinfos[5].maxsolutions = _nj8;
13207 std::vector<int> vfree(0);
13208 solutions.AddSolution(vinfos,vfree);
13209 }
13210 }
13211 }
13212 
13213 }
13214 
13215 }
13216 }
13217 }
13218 
13219 } else
13220 {
13221 IkReal x2898=((IkReal(1.00000000000000))*(cj3));
13222 IkReal x2899=((cj7)*(r02));
13223 IkReal x2900=((cj8)*(sj7));
13224 IkReal x2901=((r01)*(sj3));
13225 IkReal x2902=((IkReal(1.00000000000000))*(sj3));
13226 IkReal x2903=((sj7)*(sj8));
13227 IkReal x2904=((cj7)*(r12));
13228 IkReal x2905=((cj7)*(cj8));
13229 IkReal x2906=((cj3)*(r10));
13230 IkReal x2907=((cj7)*(sj8));
13231 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
13232 evalcond[1]=((((IkReal(-1.00000000000000))*(r10)*(sj8)*(x2898)))+(((IkReal(-1.00000000000000))*(cj8)*(r11)*(x2898)))+(((r00)*(sj3)*(sj8)))+(((cj8)*(x2901))));
13233 evalcond[2]=((((r21)*(x2903)))+(((IkReal(-1.00000000000000))*(r20)*(x2900)))+(((cj7)*(r22))));
13234 evalcond[3]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x2903)))+(((IkReal(-1.00000000000000))*(npx)*(x2900)))+(((cj7)*(npz))));
13235 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x2902)*(x2905)))+(((IkReal(-1.00000000000000))*(r02)*(sj7)*(x2902)))+(((IkReal(-1.00000000000000))*(r11)*(x2898)*(x2907)))+(((cj3)*(r12)*(sj7)))+(((x2901)*(x2907)))+(((x2905)*(x2906))));
13236 evalcond[5]=((IkReal(-1.00000000000000))+(((sj3)*(x2899)))+(((IkReal(-1.00000000000000))*(r11)*(x2898)*(x2903)))+(((x2901)*(x2903)))+(((IkReal(-1.00000000000000))*(x2898)*(x2904)))+(((IkReal(-1.00000000000000))*(r00)*(x2900)*(x2902)))+(((x2900)*(x2906))));
13237 evalcond[6]=((((IkReal(-1.00000000000000))*(x2902)*(x2904)))+(((r10)*(sj3)*(x2900)))+(((IkReal(-1.00000000000000))*(r01)*(x2898)*(x2903)))+(((cj3)*(r00)*(x2900)))+(((IkReal(-1.00000000000000))*(x2898)*(x2899)))+(((IkReal(-1.00000000000000))*(r11)*(x2902)*(x2903))));
13238 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
13239 {
13240 {
13241 IkReal j5array[1], cj5array[1], sj5array[1];
13242 bool j5valid[1]={false};
13243 _nj5 = 1;
13244 IkReal x2908=((IkReal(4.00000000000000))*(npx));
13245 IkReal x2909=((IkReal(4.00000000000000))*(npy));
13246 if( IKabs(((IkReal(0.120000000000000))+(((sj8)*(x2908)))+(((cj8)*(x2909))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((cj7)*(cj8)*(x2908)))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2909)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((sj8)*(x2908)))+(((cj8)*(x2909)))))+IKsqr(((IkReal(-0.940000000000000))+(((cj7)*(cj8)*(x2908)))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2909)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
13247  continue;
13248 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((sj8)*(x2908)))+(((cj8)*(x2909)))), ((IkReal(-0.940000000000000))+(((cj7)*(cj8)*(x2908)))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x2909)))+(((IkReal(-0.360000000000000))*(cj7)))));
13249 sj5array[0]=IKsin(j5array[0]);
13250 cj5array[0]=IKcos(j5array[0]);
13251 if( j5array[0] > IKPI )
13252 {
13253  j5array[0]-=IK2PI;
13254 }
13255 else if( j5array[0] < -IKPI )
13256 { j5array[0]+=IK2PI;
13257 }
13258 j5valid[0] = true;
13259 for(int ij5 = 0; ij5 < 1; ++ij5)
13260 {
13261 if( !j5valid[ij5] )
13262 {
13263  continue;
13264 }
13265 _ij5[0] = ij5; _ij5[1] = -1;
13266 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13267 {
13268 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13269 {
13270  j5valid[iij5]=false; _ij5[1] = iij5; break;
13271 }
13272 }
13273 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13274 {
13275 IkReal evalcond[2];
13276 evalcond[0]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(IKsin(j5)))));
13277 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(cj8)*(npx)))+(((cj7)*(npy)*(sj8)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
13278 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
13279 {
13280 continue;
13281 }
13282 }
13283 
13284 {
13285 IkReal dummyeval[1];
13286 IkReal gconst58;
13287 gconst58=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
13288 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
13289 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
13290 {
13291 {
13292 IkReal dummyeval[1];
13293 IkReal gconst59;
13294 gconst59=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
13295 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
13296 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
13297 {
13298 continue;
13299 
13300 } else
13301 {
13302 {
13303 IkReal j4array[1], cj4array[1], sj4array[1];
13304 bool j4valid[1]={false};
13305 _nj4 = 1;
13306 IkReal x2910=((IkReal(1.00000000000000))*(sj5));
13307 IkReal x2911=((r20)*(sj8));
13308 IkReal x2912=((cj5)*(cj8));
13309 IkReal x2913=((r11)*(sj3));
13310 IkReal x2914=((cj3)*(r01));
13311 IkReal x2915=((cj3)*(r00)*(sj8));
13312 IkReal x2916=((r10)*(sj3)*(sj8));
13313 if( IKabs(((gconst59)*(((((IkReal(-1.00000000000000))*(cj5)*(x2911)))+(((IkReal(-1.00000000000000))*(cj8)*(x2910)*(x2913)))+(((IkReal(-1.00000000000000))*(cj8)*(x2910)*(x2914)))+(((IkReal(-1.00000000000000))*(r21)*(x2912)))+(((IkReal(-1.00000000000000))*(x2910)*(x2916)))+(((IkReal(-1.00000000000000))*(x2910)*(x2915))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst59)*(((((x2912)*(x2914)))+(((x2912)*(x2913)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2910)))+(((IkReal(-1.00000000000000))*(x2910)*(x2911)))+(((cj5)*(x2915)))+(((cj5)*(x2916))))))) < IKFAST_ATAN2_MAGTHRESH )
13314  continue;
13315 j4array[0]=IKatan2(((gconst59)*(((((IkReal(-1.00000000000000))*(cj5)*(x2911)))+(((IkReal(-1.00000000000000))*(cj8)*(x2910)*(x2913)))+(((IkReal(-1.00000000000000))*(cj8)*(x2910)*(x2914)))+(((IkReal(-1.00000000000000))*(r21)*(x2912)))+(((IkReal(-1.00000000000000))*(x2910)*(x2916)))+(((IkReal(-1.00000000000000))*(x2910)*(x2915)))))), ((gconst59)*(((((x2912)*(x2914)))+(((x2912)*(x2913)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x2910)))+(((IkReal(-1.00000000000000))*(x2910)*(x2911)))+(((cj5)*(x2915)))+(((cj5)*(x2916)))))));
13316 sj4array[0]=IKsin(j4array[0]);
13317 cj4array[0]=IKcos(j4array[0]);
13318 if( j4array[0] > IKPI )
13319 {
13320  j4array[0]-=IK2PI;
13321 }
13322 else if( j4array[0] < -IKPI )
13323 { j4array[0]+=IK2PI;
13324 }
13325 j4valid[0] = true;
13326 for(int ij4 = 0; ij4 < 1; ++ij4)
13327 {
13328 if( !j4valid[ij4] )
13329 {
13330  continue;
13331 }
13332 _ij4[0] = ij4; _ij4[1] = -1;
13333 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13334 {
13335 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13336 {
13337  j4valid[iij4]=false; _ij4[1] = iij4; break;
13338 }
13339 }
13340 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13341 {
13342 IkReal evalcond[4];
13343 IkReal x2917=IKsin(j4);
13344 IkReal x2918=IKcos(j4);
13345 IkReal x2919=((IkReal(1.00000000000000))*(cj8));
13346 IkReal x2920=((cj3)*(r01));
13347 IkReal x2921=((cj3)*(r00));
13348 IkReal x2922=((cj7)*(cj8));
13349 IkReal x2923=((r11)*(sj3));
13350 IkReal x2924=((IkReal(1.00000000000000))*(sj8));
13351 IkReal x2925=((r10)*(sj3));
13352 IkReal x2926=((sj5)*(x2918));
13353 IkReal x2927=((cj5)*(x2917));
13354 IkReal x2928=((cj5)*(x2918));
13355 IkReal x2929=((sj5)*(x2917));
13356 IkReal x2930=((x2927)+(x2926));
13357 evalcond[0]=((((cj8)*(r21)))+(((r20)*(sj8)))+(x2930));
13358 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8)))+(x2929)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2919)))+(((IkReal(-1.00000000000000))*(x2928))));
13359 evalcond[2]=((((IkReal(-1.00000000000000))*(x2921)*(x2924)))+(((IkReal(-1.00000000000000))*(x2919)*(x2920)))+(((IkReal(-1.00000000000000))*(x2919)*(x2923)))+(((IkReal(-1.00000000000000))*(x2924)*(x2925)))+(x2928)+(((IkReal(-1.00000000000000))*(x2929))));
13360 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x2921)*(x2922)))+(((IkReal(-1.00000000000000))*(cj7)*(x2920)*(x2924)))+(((IkReal(-1.00000000000000))*(cj7)*(x2923)*(x2924)))+(((cj3)*(r02)*(sj7)))+(((x2922)*(x2925)))+(x2930));
13361 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
13362 {
13363 continue;
13364 }
13365 }
13366 
13367 {
13368 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13369 vinfos[0].jointtype = 1;
13370 vinfos[0].foffset = j3;
13371 vinfos[0].indices[0] = _ij3[0];
13372 vinfos[0].indices[1] = _ij3[1];
13373 vinfos[0].maxsolutions = _nj3;
13374 vinfos[1].jointtype = 1;
13375 vinfos[1].foffset = j4;
13376 vinfos[1].indices[0] = _ij4[0];
13377 vinfos[1].indices[1] = _ij4[1];
13378 vinfos[1].maxsolutions = _nj4;
13379 vinfos[2].jointtype = 1;
13380 vinfos[2].foffset = j5;
13381 vinfos[2].indices[0] = _ij5[0];
13382 vinfos[2].indices[1] = _ij5[1];
13383 vinfos[2].maxsolutions = _nj5;
13384 vinfos[3].jointtype = 1;
13385 vinfos[3].foffset = j6;
13386 vinfos[3].indices[0] = _ij6[0];
13387 vinfos[3].indices[1] = _ij6[1];
13388 vinfos[3].maxsolutions = _nj6;
13389 vinfos[4].jointtype = 1;
13390 vinfos[4].foffset = j7;
13391 vinfos[4].indices[0] = _ij7[0];
13392 vinfos[4].indices[1] = _ij7[1];
13393 vinfos[4].maxsolutions = _nj7;
13394 vinfos[5].jointtype = 1;
13395 vinfos[5].foffset = j8;
13396 vinfos[5].indices[0] = _ij8[0];
13397 vinfos[5].indices[1] = _ij8[1];
13398 vinfos[5].maxsolutions = _nj8;
13399 std::vector<int> vfree(0);
13400 solutions.AddSolution(vinfos,vfree);
13401 }
13402 }
13403 }
13404 
13405 }
13406 
13407 }
13408 
13409 } else
13410 {
13411 {
13412 IkReal j4array[1], cj4array[1], sj4array[1];
13413 bool j4valid[1]={false};
13414 _nj4 = 1;
13415 IkReal x2931=((r22)*(sj7));
13416 IkReal x2932=((cj8)*(sj5));
13417 IkReal x2933=((sj5)*(sj8));
13418 IkReal x2934=((cj7)*(r20));
13419 IkReal x2935=((cj5)*(cj8));
13420 IkReal x2936=((cj7)*(r21));
13421 IkReal x2937=((cj5)*(sj8));
13422 if( IKabs(((gconst58)*(((((IkReal(-1.00000000000000))*(sj5)*(x2931)))+(((r21)*(x2935)))+(((IkReal(-1.00000000000000))*(x2932)*(x2934)))+(((r20)*(x2937)))+(((x2933)*(x2936))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst58)*(((((r21)*(x2932)))+(((cj5)*(x2931)))+(((r20)*(x2933)))+(((IkReal(-1.00000000000000))*(x2936)*(x2937)))+(((x2934)*(x2935))))))) < IKFAST_ATAN2_MAGTHRESH )
13423  continue;
13424 j4array[0]=IKatan2(((gconst58)*(((((IkReal(-1.00000000000000))*(sj5)*(x2931)))+(((r21)*(x2935)))+(((IkReal(-1.00000000000000))*(x2932)*(x2934)))+(((r20)*(x2937)))+(((x2933)*(x2936)))))), ((gconst58)*(((((r21)*(x2932)))+(((cj5)*(x2931)))+(((r20)*(x2933)))+(((IkReal(-1.00000000000000))*(x2936)*(x2937)))+(((x2934)*(x2935)))))));
13425 sj4array[0]=IKsin(j4array[0]);
13426 cj4array[0]=IKcos(j4array[0]);
13427 if( j4array[0] > IKPI )
13428 {
13429  j4array[0]-=IK2PI;
13430 }
13431 else if( j4array[0] < -IKPI )
13432 { j4array[0]+=IK2PI;
13433 }
13434 j4valid[0] = true;
13435 for(int ij4 = 0; ij4 < 1; ++ij4)
13436 {
13437 if( !j4valid[ij4] )
13438 {
13439  continue;
13440 }
13441 _ij4[0] = ij4; _ij4[1] = -1;
13442 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13443 {
13444 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13445 {
13446  j4valid[iij4]=false; _ij4[1] = iij4; break;
13447 }
13448 }
13449 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13450 {
13451 IkReal evalcond[4];
13452 IkReal x2938=IKsin(j4);
13453 IkReal x2939=IKcos(j4);
13454 IkReal x2940=((IkReal(1.00000000000000))*(cj8));
13455 IkReal x2941=((cj3)*(r01));
13456 IkReal x2942=((cj3)*(r00));
13457 IkReal x2943=((cj7)*(cj8));
13458 IkReal x2944=((r11)*(sj3));
13459 IkReal x2945=((IkReal(1.00000000000000))*(sj8));
13460 IkReal x2946=((r10)*(sj3));
13461 IkReal x2947=((sj5)*(x2939));
13462 IkReal x2948=((cj5)*(x2938));
13463 IkReal x2949=((cj5)*(x2939));
13464 IkReal x2950=((sj5)*(x2938));
13465 IkReal x2951=((x2948)+(x2947));
13466 evalcond[0]=((((cj8)*(r21)))+(((r20)*(sj8)))+(x2951));
13467 evalcond[1]=((((IkReal(-1.00000000000000))*(x2949)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x2940)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8)))+(x2950));
13468 evalcond[2]=((((IkReal(-1.00000000000000))*(x2950)))+(((IkReal(-1.00000000000000))*(x2940)*(x2941)))+(((IkReal(-1.00000000000000))*(x2940)*(x2944)))+(((IkReal(-1.00000000000000))*(x2942)*(x2945)))+(((IkReal(-1.00000000000000))*(x2945)*(x2946)))+(x2949));
13469 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x2941)*(x2945)))+(((IkReal(-1.00000000000000))*(cj7)*(x2944)*(x2945)))+(((cj3)*(r02)*(sj7)))+(((x2943)*(x2946)))+(((x2942)*(x2943)))+(x2951));
13470 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
13471 {
13472 continue;
13473 }
13474 }
13475 
13476 {
13477 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13478 vinfos[0].jointtype = 1;
13479 vinfos[0].foffset = j3;
13480 vinfos[0].indices[0] = _ij3[0];
13481 vinfos[0].indices[1] = _ij3[1];
13482 vinfos[0].maxsolutions = _nj3;
13483 vinfos[1].jointtype = 1;
13484 vinfos[1].foffset = j4;
13485 vinfos[1].indices[0] = _ij4[0];
13486 vinfos[1].indices[1] = _ij4[1];
13487 vinfos[1].maxsolutions = _nj4;
13488 vinfos[2].jointtype = 1;
13489 vinfos[2].foffset = j5;
13490 vinfos[2].indices[0] = _ij5[0];
13491 vinfos[2].indices[1] = _ij5[1];
13492 vinfos[2].maxsolutions = _nj5;
13493 vinfos[3].jointtype = 1;
13494 vinfos[3].foffset = j6;
13495 vinfos[3].indices[0] = _ij6[0];
13496 vinfos[3].indices[1] = _ij6[1];
13497 vinfos[3].maxsolutions = _nj6;
13498 vinfos[4].jointtype = 1;
13499 vinfos[4].foffset = j7;
13500 vinfos[4].indices[0] = _ij7[0];
13501 vinfos[4].indices[1] = _ij7[1];
13502 vinfos[4].maxsolutions = _nj7;
13503 vinfos[5].jointtype = 1;
13504 vinfos[5].foffset = j8;
13505 vinfos[5].indices[0] = _ij8[0];
13506 vinfos[5].indices[1] = _ij8[1];
13507 vinfos[5].maxsolutions = _nj8;
13508 std::vector<int> vfree(0);
13509 solutions.AddSolution(vinfos,vfree);
13510 }
13511 }
13512 }
13513 
13514 }
13515 
13516 }
13517 }
13518 }
13519 
13520 } else
13521 {
13522 IkReal x2952=((cj3)*(cj8));
13523 IkReal x2953=((r01)*(sj3));
13524 IkReal x2954=((r02)*(sj3));
13525 IkReal x2955=((IkReal(1.00000000000000))*(sj7));
13526 IkReal x2956=((IkReal(1.00000000000000))*(r11));
13527 IkReal x2957=((cj3)*(r12));
13528 IkReal x2958=((IkReal(1.00000000000000))*(cj7));
13529 IkReal x2959=((cj8)*(sj3));
13530 IkReal x2960=((sj3)*(sj8));
13531 IkReal x2961=((IkReal(1.00000000000000))*(cj3)*(sj8));
13532 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
13533 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
13534 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
13535 evalcond[3]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x2952)*(x2956)))+(((r00)*(x2960)))+(((cj8)*(x2953)))+(((IkReal(-1.00000000000000))*(r10)*(x2961))));
13536 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x2952)))+(((IkReal(-1.00000000000000))*(r00)*(x2961)))+(((IkReal(-1.00000000000000))*(x2956)*(x2959)))+(((IkReal(-1.00000000000000))*(r10)*(x2960))));
13537 evalcond[5]=((((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x2956)))+(((sj7)*(x2957)))+(((IkReal(-1.00000000000000))*(x2954)*(x2955)))+(((cj7)*(r10)*(x2952)))+(((cj7)*(sj8)*(x2953)))+(((IkReal(-1.00000000000000))*(r00)*(x2958)*(x2959))));
13538 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x2955)*(x2959)))+(((cj7)*(x2954)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x2955)))+(((sj7)*(sj8)*(x2953)))+(((r10)*(sj7)*(x2952)))+(((IkReal(-1.00000000000000))*(x2957)*(x2958))));
13539 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
13540 {
13541 {
13542 IkReal j5array[1], cj5array[1], sj5array[1];
13543 bool j5valid[1]={false};
13544 _nj5 = 1;
13545 IkReal x2962=((IkReal(4.00000000000000))*(sj7));
13546 IkReal x2963=((npy)*(sj8));
13547 IkReal x2964=((IkReal(4.00000000000000))*(cj7));
13548 IkReal x2965=((cj8)*(npx));
13549 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj7)))+(((npz)*(x2964)))+(((x2962)*(x2963)))+(((IkReal(-1.00000000000000))*(x2962)*(x2965))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x2963)*(x2964)))+(((npz)*(x2962)))+(((x2964)*(x2965)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj7)))+(((npz)*(x2964)))+(((x2962)*(x2963)))+(((IkReal(-1.00000000000000))*(x2962)*(x2965)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x2963)*(x2964)))+(((npz)*(x2962)))+(((x2964)*(x2965)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
13550  continue;
13551 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj7)))+(((npz)*(x2964)))+(((x2962)*(x2963)))+(((IkReal(-1.00000000000000))*(x2962)*(x2965)))), ((IkReal(-0.940000000000000))+(((IkReal(-1.00000000000000))*(x2963)*(x2964)))+(((npz)*(x2962)))+(((x2964)*(x2965)))+(((IkReal(-0.360000000000000))*(cj7)))));
13552 sj5array[0]=IKsin(j5array[0]);
13553 cj5array[0]=IKcos(j5array[0]);
13554 if( j5array[0] > IKPI )
13555 {
13556  j5array[0]-=IK2PI;
13557 }
13558 else if( j5array[0] < -IKPI )
13559 { j5array[0]+=IK2PI;
13560 }
13561 j5valid[0] = true;
13562 for(int ij5 = 0; ij5 < 1; ++ij5)
13563 {
13564 if( !j5valid[ij5] )
13565 {
13566  continue;
13567 }
13568 _ij5[0] = ij5; _ij5[1] = -1;
13569 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13570 {
13571 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13572 {
13573  j5valid[iij5]=false; _ij5[1] = iij5; break;
13574 }
13575 }
13576 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13577 {
13578 IkReal evalcond[2];
13579 IkReal x2966=((IkReal(1.00000000000000))*(sj7));
13580 IkReal x2967=((npy)*(sj8));
13581 IkReal x2968=((cj8)*(npx));
13582 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(cj7)*(x2968)))+(((IkReal(0.0900000000000000))*(cj7)))+(((cj7)*(x2967)))+(((IkReal(-1.00000000000000))*(npz)*(x2966)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
13583 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x2967)))+(((IkReal(-0.250000000000000))*(IKsin(j5))))+(((IkReal(-1.00000000000000))*(x2966)*(x2968)))+(((cj7)*(npz))));
13584 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
13585 {
13586 continue;
13587 }
13588 }
13589 
13590 {
13591 IkReal dummyeval[1];
13592 IkReal gconst60;
13593 gconst60=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
13594 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
13595 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
13596 {
13597 {
13598 IkReal dummyeval[1];
13599 IkReal gconst61;
13600 gconst61=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
13601 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
13602 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
13603 {
13604 continue;
13605 
13606 } else
13607 {
13608 {
13609 IkReal j4array[1], cj4array[1], sj4array[1];
13610 bool j4valid[1]={false};
13611 _nj4 = 1;
13612 IkReal x2969=((cj3)*(cj5));
13613 IkReal x2970=((r02)*(sj7));
13614 IkReal x2971=((cj8)*(r00));
13615 IkReal x2972=((cj5)*(sj7));
13616 IkReal x2973=((cj5)*(sj3));
13617 IkReal x2974=((cj7)*(cj8));
13618 IkReal x2975=((IkReal(1.00000000000000))*(sj5));
13619 IkReal x2976=((r12)*(sj3));
13620 IkReal x2977=((sj3)*(sj5));
13621 IkReal x2978=((cj3)*(cj7)*(sj5));
13622 IkReal x2979=((IkReal(1.00000000000000))*(cj7)*(sj8));
13623 if( IKabs(((gconst61)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x2974)*(x2975)))+(((cj7)*(x2969)*(x2971)))+(((IkReal(-1.00000000000000))*(r11)*(x2973)*(x2979)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2975)))+(((x2969)*(x2970)))+(((r10)*(x2973)*(x2974)))+(((IkReal(-1.00000000000000))*(r01)*(x2969)*(x2979)))+(((x2972)*(x2976))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst61)*(((((cj5)*(r20)*(x2974)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x2975)))+(((r10)*(x2974)*(x2977)))+(((x2971)*(x2978)))+(((sj5)*(sj7)*(x2976)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2979)))+(((r22)*(x2972)))+(((cj3)*(sj5)*(x2970)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2975))))))) < IKFAST_ATAN2_MAGTHRESH )
13624  continue;
13625 j4array[0]=IKatan2(((gconst61)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x2974)*(x2975)))+(((cj7)*(x2969)*(x2971)))+(((IkReal(-1.00000000000000))*(r11)*(x2973)*(x2979)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x2975)))+(((x2969)*(x2970)))+(((r10)*(x2973)*(x2974)))+(((IkReal(-1.00000000000000))*(r01)*(x2969)*(x2979)))+(((x2972)*(x2976)))))), ((gconst61)*(((((cj5)*(r20)*(x2974)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x2975)))+(((r10)*(x2974)*(x2977)))+(((x2971)*(x2978)))+(((sj5)*(sj7)*(x2976)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2979)))+(((r22)*(x2972)))+(((cj3)*(sj5)*(x2970)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x2975)))))));
13626 sj4array[0]=IKsin(j4array[0]);
13627 cj4array[0]=IKcos(j4array[0]);
13628 if( j4array[0] > IKPI )
13629 {
13630  j4array[0]-=IK2PI;
13631 }
13632 else if( j4array[0] < -IKPI )
13633 { j4array[0]+=IK2PI;
13634 }
13635 j4valid[0] = true;
13636 for(int ij4 = 0; ij4 < 1; ++ij4)
13637 {
13638 if( !j4valid[ij4] )
13639 {
13640  continue;
13641 }
13642 _ij4[0] = ij4; _ij4[1] = -1;
13643 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13644 {
13645 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13646 {
13647  j4valid[iij4]=false; _ij4[1] = iij4; break;
13648 }
13649 }
13650 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13651 {
13652 IkReal evalcond[4];
13653 IkReal x2980=IKcos(j4);
13654 IkReal x2981=IKsin(j4);
13655 IkReal x2982=((IkReal(1.00000000000000))*(cj7));
13656 IkReal x2983=((cj8)*(r20));
13657 IkReal x2984=((cj3)*(r02));
13658 IkReal x2985=((IkReal(1.00000000000000))*(sj7));
13659 IkReal x2986=((sj3)*(sj7));
13660 IkReal x2987=((r21)*(sj8));
13661 IkReal x2988=((cj8)*(r10));
13662 IkReal x2989=((sj5)*(x2980));
13663 IkReal x2990=((cj5)*(x2981));
13664 IkReal x2991=((r11)*(sj3)*(sj8));
13665 IkReal x2992=((cj3)*(cj8)*(r00));
13666 IkReal x2993=((cj5)*(x2980));
13667 IkReal x2994=((cj3)*(r01)*(sj8));
13668 IkReal x2995=((sj5)*(x2981));
13669 IkReal x2996=((x2989)+(x2990));
13670 evalcond[0]=((((IkReal(-1.00000000000000))*(x2982)*(x2983)))+(((IkReal(-1.00000000000000))*(r22)*(x2985)))+(((IkReal(-1.00000000000000))*(x2993)))+(x2995)+(((cj7)*(x2987))));
13671 evalcond[1]=((((sj7)*(x2987)))+(((IkReal(-1.00000000000000))*(x2983)*(x2985)))+(((cj7)*(r22)))+(x2996));
13672 evalcond[2]=((((cj7)*(x2992)))+(((cj7)*(sj3)*(x2988)))+(((sj7)*(x2984)))+(((r12)*(x2986)))+(((IkReal(-1.00000000000000))*(x2982)*(x2994)))+(((IkReal(-1.00000000000000))*(x2982)*(x2991)))+(x2996));
13673 evalcond[3]=((((IkReal(-1.00000000000000))*(x2982)*(x2984)))+(((IkReal(-1.00000000000000))*(x2985)*(x2991)))+(((IkReal(-1.00000000000000))*(x2985)*(x2994)))+(((x2986)*(x2988)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x2982)))+(((sj7)*(x2992)))+(((IkReal(-1.00000000000000))*(x2995)))+(x2993));
13674 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
13675 {
13676 continue;
13677 }
13678 }
13679 
13680 {
13681 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13682 vinfos[0].jointtype = 1;
13683 vinfos[0].foffset = j3;
13684 vinfos[0].indices[0] = _ij3[0];
13685 vinfos[0].indices[1] = _ij3[1];
13686 vinfos[0].maxsolutions = _nj3;
13687 vinfos[1].jointtype = 1;
13688 vinfos[1].foffset = j4;
13689 vinfos[1].indices[0] = _ij4[0];
13690 vinfos[1].indices[1] = _ij4[1];
13691 vinfos[1].maxsolutions = _nj4;
13692 vinfos[2].jointtype = 1;
13693 vinfos[2].foffset = j5;
13694 vinfos[2].indices[0] = _ij5[0];
13695 vinfos[2].indices[1] = _ij5[1];
13696 vinfos[2].maxsolutions = _nj5;
13697 vinfos[3].jointtype = 1;
13698 vinfos[3].foffset = j6;
13699 vinfos[3].indices[0] = _ij6[0];
13700 vinfos[3].indices[1] = _ij6[1];
13701 vinfos[3].maxsolutions = _nj6;
13702 vinfos[4].jointtype = 1;
13703 vinfos[4].foffset = j7;
13704 vinfos[4].indices[0] = _ij7[0];
13705 vinfos[4].indices[1] = _ij7[1];
13706 vinfos[4].maxsolutions = _nj7;
13707 vinfos[5].jointtype = 1;
13708 vinfos[5].foffset = j8;
13709 vinfos[5].indices[0] = _ij8[0];
13710 vinfos[5].indices[1] = _ij8[1];
13711 vinfos[5].maxsolutions = _nj8;
13712 std::vector<int> vfree(0);
13713 solutions.AddSolution(vinfos,vfree);
13714 }
13715 }
13716 }
13717 
13718 }
13719 
13720 }
13721 
13722 } else
13723 {
13724 {
13725 IkReal j4array[1], cj4array[1], sj4array[1];
13726 bool j4valid[1]={false};
13727 _nj4 = 1;
13728 IkReal x2997=((sj5)*(sj7));
13729 IkReal x2998=((r21)*(sj8));
13730 IkReal x2999=((cj5)*(sj7));
13731 IkReal x3000=((cj8)*(r20));
13732 IkReal x3001=((cj5)*(cj7));
13733 IkReal x3002=((cj7)*(sj5));
13734 if( IKabs(((gconst60)*(((((x2998)*(x3002)))+(((IkReal(-1.00000000000000))*(x3000)*(x3002)))+(((IkReal(-1.00000000000000))*(r22)*(x2997)))+(((r22)*(x3001)))+(((IkReal(-1.00000000000000))*(x2999)*(x3000)))+(((x2998)*(x2999))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst60)*(((((IkReal(-1.00000000000000))*(x2998)*(x3001)))+(((r22)*(x3002)))+(((x3000)*(x3001)))+(((IkReal(-1.00000000000000))*(x2997)*(x3000)))+(((x2997)*(x2998)))+(((r22)*(x2999))))))) < IKFAST_ATAN2_MAGTHRESH )
13735  continue;
13736 j4array[0]=IKatan2(((gconst60)*(((((x2998)*(x3002)))+(((IkReal(-1.00000000000000))*(x3000)*(x3002)))+(((IkReal(-1.00000000000000))*(r22)*(x2997)))+(((r22)*(x3001)))+(((IkReal(-1.00000000000000))*(x2999)*(x3000)))+(((x2998)*(x2999)))))), ((gconst60)*(((((IkReal(-1.00000000000000))*(x2998)*(x3001)))+(((r22)*(x3002)))+(((x3000)*(x3001)))+(((IkReal(-1.00000000000000))*(x2997)*(x3000)))+(((x2997)*(x2998)))+(((r22)*(x2999)))))));
13737 sj4array[0]=IKsin(j4array[0]);
13738 cj4array[0]=IKcos(j4array[0]);
13739 if( j4array[0] > IKPI )
13740 {
13741  j4array[0]-=IK2PI;
13742 }
13743 else if( j4array[0] < -IKPI )
13744 { j4array[0]+=IK2PI;
13745 }
13746 j4valid[0] = true;
13747 for(int ij4 = 0; ij4 < 1; ++ij4)
13748 {
13749 if( !j4valid[ij4] )
13750 {
13751  continue;
13752 }
13753 _ij4[0] = ij4; _ij4[1] = -1;
13754 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13755 {
13756 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13757 {
13758  j4valid[iij4]=false; _ij4[1] = iij4; break;
13759 }
13760 }
13761 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13762 {
13763 IkReal evalcond[4];
13764 IkReal x3003=IKcos(j4);
13765 IkReal x3004=IKsin(j4);
13766 IkReal x3005=((IkReal(1.00000000000000))*(cj7));
13767 IkReal x3006=((cj8)*(r20));
13768 IkReal x3007=((cj3)*(r02));
13769 IkReal x3008=((IkReal(1.00000000000000))*(sj7));
13770 IkReal x3009=((sj3)*(sj7));
13771 IkReal x3010=((r21)*(sj8));
13772 IkReal x3011=((cj8)*(r10));
13773 IkReal x3012=((sj5)*(x3003));
13774 IkReal x3013=((cj5)*(x3004));
13775 IkReal x3014=((r11)*(sj3)*(sj8));
13776 IkReal x3015=((cj3)*(cj8)*(r00));
13777 IkReal x3016=((cj5)*(x3003));
13778 IkReal x3017=((cj3)*(r01)*(sj8));
13779 IkReal x3018=((sj5)*(x3004));
13780 IkReal x3019=((x3012)+(x3013));
13781 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x3008)))+(x3018)+(((cj7)*(x3010)))+(((IkReal(-1.00000000000000))*(x3005)*(x3006)))+(((IkReal(-1.00000000000000))*(x3016))));
13782 evalcond[1]=((((sj7)*(x3010)))+(x3019)+(((IkReal(-1.00000000000000))*(x3006)*(x3008)))+(((cj7)*(r22))));
13783 evalcond[2]=((((cj7)*(sj3)*(x3011)))+(((sj7)*(x3007)))+(x3019)+(((cj7)*(x3015)))+(((r12)*(x3009)))+(((IkReal(-1.00000000000000))*(x3005)*(x3017)))+(((IkReal(-1.00000000000000))*(x3005)*(x3014))));
13784 evalcond[3]=((((sj7)*(x3015)))+(((x3009)*(x3011)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3005)))+(x3016)+(((IkReal(-1.00000000000000))*(x3005)*(x3007)))+(((IkReal(-1.00000000000000))*(x3008)*(x3017)))+(((IkReal(-1.00000000000000))*(x3008)*(x3014)))+(((IkReal(-1.00000000000000))*(x3018))));
13785 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
13786 {
13787 continue;
13788 }
13789 }
13790 
13791 {
13792 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13793 vinfos[0].jointtype = 1;
13794 vinfos[0].foffset = j3;
13795 vinfos[0].indices[0] = _ij3[0];
13796 vinfos[0].indices[1] = _ij3[1];
13797 vinfos[0].maxsolutions = _nj3;
13798 vinfos[1].jointtype = 1;
13799 vinfos[1].foffset = j4;
13800 vinfos[1].indices[0] = _ij4[0];
13801 vinfos[1].indices[1] = _ij4[1];
13802 vinfos[1].maxsolutions = _nj4;
13803 vinfos[2].jointtype = 1;
13804 vinfos[2].foffset = j5;
13805 vinfos[2].indices[0] = _ij5[0];
13806 vinfos[2].indices[1] = _ij5[1];
13807 vinfos[2].maxsolutions = _nj5;
13808 vinfos[3].jointtype = 1;
13809 vinfos[3].foffset = j6;
13810 vinfos[3].indices[0] = _ij6[0];
13811 vinfos[3].indices[1] = _ij6[1];
13812 vinfos[3].maxsolutions = _nj6;
13813 vinfos[4].jointtype = 1;
13814 vinfos[4].foffset = j7;
13815 vinfos[4].indices[0] = _ij7[0];
13816 vinfos[4].indices[1] = _ij7[1];
13817 vinfos[4].maxsolutions = _nj7;
13818 vinfos[5].jointtype = 1;
13819 vinfos[5].foffset = j8;
13820 vinfos[5].indices[0] = _ij8[0];
13821 vinfos[5].indices[1] = _ij8[1];
13822 vinfos[5].maxsolutions = _nj8;
13823 std::vector<int> vfree(0);
13824 solutions.AddSolution(vinfos,vfree);
13825 }
13826 }
13827 }
13828 
13829 }
13830 
13831 }
13832 }
13833 }
13834 
13835 } else
13836 {
13837 IkReal x3020=((cj3)*(cj8));
13838 IkReal x3021=((r01)*(sj3));
13839 IkReal x3022=((r02)*(sj3));
13840 IkReal x3023=((IkReal(1.00000000000000))*(sj7));
13841 IkReal x3024=((IkReal(1.00000000000000))*(r11));
13842 IkReal x3025=((cj3)*(r12));
13843 IkReal x3026=((IkReal(1.00000000000000))*(cj7));
13844 IkReal x3027=((cj8)*(sj3));
13845 IkReal x3028=((sj3)*(sj8));
13846 IkReal x3029=((IkReal(1.00000000000000))*(cj3)*(sj8));
13847 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
13848 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
13849 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
13850 evalcond[3]=((IkReal(-1.00000000000000))+(((cj8)*(x3021)))+(((IkReal(-1.00000000000000))*(x3020)*(x3024)))+(((r00)*(x3028)))+(((IkReal(-1.00000000000000))*(r10)*(x3029))));
13851 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x3029)))+(((IkReal(-1.00000000000000))*(r01)*(x3020)))+(((IkReal(-1.00000000000000))*(x3024)*(x3027)))+(((IkReal(-1.00000000000000))*(r10)*(x3028))));
13852 evalcond[5]=((((cj7)*(sj8)*(x3021)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x3024)))+(((cj7)*(r10)*(x3020)))+(((sj7)*(x3025)))+(((IkReal(-1.00000000000000))*(x3022)*(x3023)))+(((IkReal(-1.00000000000000))*(r00)*(x3026)*(x3027))));
13853 evalcond[6]=((((sj7)*(sj8)*(x3021)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x3023)))+(((IkReal(-1.00000000000000))*(x3025)*(x3026)))+(((r10)*(sj7)*(x3020)))+(((IkReal(-1.00000000000000))*(r00)*(x3023)*(x3027)))+(((cj7)*(x3022))));
13854 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 )
13855 {
13856 {
13857 IkReal j5array[1], cj5array[1], sj5array[1];
13858 bool j5valid[1]={false};
13859 _nj5 = 1;
13860 IkReal x3030=((IkReal(4.00000000000000))*(sj7));
13861 IkReal x3031=((npy)*(sj8));
13862 IkReal x3032=((IkReal(4.00000000000000))*(cj7));
13863 IkReal x3033=((cj8)*(npx));
13864 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3032)))+(((x3030)*(x3033)))+(((IkReal(-1.00000000000000))*(x3030)*(x3031)))+(((IkReal(-0.360000000000000))*(sj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((x3032)*(x3033)))+(((npz)*(x3030)))+(((IkReal(-1.00000000000000))*(x3031)*(x3032)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3032)))+(((x3030)*(x3033)))+(((IkReal(-1.00000000000000))*(x3030)*(x3031)))+(((IkReal(-0.360000000000000))*(sj7)))))+IKsqr(((IkReal(-0.940000000000000))+(((x3032)*(x3033)))+(((npz)*(x3030)))+(((IkReal(-1.00000000000000))*(x3031)*(x3032)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
13865  continue;
13866 j5array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3032)))+(((x3030)*(x3033)))+(((IkReal(-1.00000000000000))*(x3030)*(x3031)))+(((IkReal(-0.360000000000000))*(sj7)))), ((IkReal(-0.940000000000000))+(((x3032)*(x3033)))+(((npz)*(x3030)))+(((IkReal(-1.00000000000000))*(x3031)*(x3032)))+(((IkReal(-0.360000000000000))*(cj7)))));
13867 sj5array[0]=IKsin(j5array[0]);
13868 cj5array[0]=IKcos(j5array[0]);
13869 if( j5array[0] > IKPI )
13870 {
13871  j5array[0]-=IK2PI;
13872 }
13873 else if( j5array[0] < -IKPI )
13874 { j5array[0]+=IK2PI;
13875 }
13876 j5valid[0] = true;
13877 for(int ij5 = 0; ij5 < 1; ++ij5)
13878 {
13879 if( !j5valid[ij5] )
13880 {
13881  continue;
13882 }
13883 _ij5[0] = ij5; _ij5[1] = -1;
13884 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13885 {
13886 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13887 {
13888  j5valid[iij5]=false; _ij5[1] = iij5; break;
13889 }
13890 }
13891 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13892 {
13893 IkReal evalcond[2];
13894 IkReal x3034=((IkReal(1.00000000000000))*(sj7));
13895 IkReal x3035=((npy)*(sj8));
13896 IkReal x3036=((cj8)*(npx));
13897 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3034)))+(((IkReal(0.0900000000000000))*(cj7)))+(((cj7)*(x3035)))+(((IkReal(-1.00000000000000))*(cj7)*(x3036)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
13898 evalcond[1]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(0.250000000000000))*(IKsin(j5))))+(((sj7)*(x3035)))+(((cj7)*(npz)))+(((IkReal(-1.00000000000000))*(x3034)*(x3036))));
13899 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
13900 {
13901 continue;
13902 }
13903 }
13904 
13905 {
13906 IkReal dummyeval[1];
13907 IkReal gconst62;
13908 gconst62=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
13909 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
13910 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
13911 {
13912 {
13913 IkReal dummyeval[1];
13914 IkReal gconst63;
13915 gconst63=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
13916 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
13917 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
13918 {
13919 continue;
13920 
13921 } else
13922 {
13923 {
13924 IkReal j4array[1], cj4array[1], sj4array[1];
13925 bool j4valid[1]={false};
13926 _nj4 = 1;
13927 IkReal x3037=((cj3)*(cj5));
13928 IkReal x3038=((r02)*(sj7));
13929 IkReal x3039=((cj8)*(r00));
13930 IkReal x3040=((cj5)*(sj7));
13931 IkReal x3041=((cj5)*(sj3));
13932 IkReal x3042=((cj7)*(cj8));
13933 IkReal x3043=((IkReal(1.00000000000000))*(sj5));
13934 IkReal x3044=((r12)*(sj3));
13935 IkReal x3045=((sj3)*(sj5));
13936 IkReal x3046=((cj3)*(cj7)*(sj5));
13937 IkReal x3047=((IkReal(1.00000000000000))*(cj7)*(sj8));
13938 if( IKabs(((gconst63)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((r10)*(x3041)*(x3042)))+(((IkReal(-1.00000000000000))*(r20)*(x3042)*(x3043)))+(((x3037)*(x3038)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x3043)))+(((IkReal(-1.00000000000000))*(r01)*(x3037)*(x3047)))+(((cj7)*(x3037)*(x3039)))+(((x3040)*(x3044)))+(((IkReal(-1.00000000000000))*(r11)*(x3041)*(x3047))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst63)*(((((r22)*(x3040)))+(((r10)*(x3042)*(x3045)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x3043)))+(((x3039)*(x3046)))+(((cj5)*(r20)*(x3042)))+(((sj5)*(sj7)*(x3044)))+(((cj3)*(sj5)*(x3038)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x3043)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3047))))))) < IKFAST_ATAN2_MAGTHRESH )
13939  continue;
13940 j4array[0]=IKatan2(((gconst63)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((r10)*(x3041)*(x3042)))+(((IkReal(-1.00000000000000))*(r20)*(x3042)*(x3043)))+(((x3037)*(x3038)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x3043)))+(((IkReal(-1.00000000000000))*(r01)*(x3037)*(x3047)))+(((cj7)*(x3037)*(x3039)))+(((x3040)*(x3044)))+(((IkReal(-1.00000000000000))*(r11)*(x3041)*(x3047)))))), ((gconst63)*(((((r22)*(x3040)))+(((r10)*(x3042)*(x3045)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x3043)))+(((x3039)*(x3046)))+(((cj5)*(r20)*(x3042)))+(((sj5)*(sj7)*(x3044)))+(((cj3)*(sj5)*(x3038)))+(((IkReal(-1.00000000000000))*(cj7)*(r11)*(sj3)*(sj8)*(x3043)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3047)))))));
13941 sj4array[0]=IKsin(j4array[0]);
13942 cj4array[0]=IKcos(j4array[0]);
13943 if( j4array[0] > IKPI )
13944 {
13945  j4array[0]-=IK2PI;
13946 }
13947 else if( j4array[0] < -IKPI )
13948 { j4array[0]+=IK2PI;
13949 }
13950 j4valid[0] = true;
13951 for(int ij4 = 0; ij4 < 1; ++ij4)
13952 {
13953 if( !j4valid[ij4] )
13954 {
13955  continue;
13956 }
13957 _ij4[0] = ij4; _ij4[1] = -1;
13958 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13959 {
13960 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13961 {
13962  j4valid[iij4]=false; _ij4[1] = iij4; break;
13963 }
13964 }
13965 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13966 {
13967 IkReal evalcond[4];
13968 IkReal x3048=IKcos(j4);
13969 IkReal x3049=IKsin(j4);
13970 IkReal x3050=((IkReal(1.00000000000000))*(cj7));
13971 IkReal x3051=((cj8)*(r20));
13972 IkReal x3052=((cj3)*(r02));
13973 IkReal x3053=((IkReal(1.00000000000000))*(sj7));
13974 IkReal x3054=((sj3)*(sj7));
13975 IkReal x3055=((r21)*(sj8));
13976 IkReal x3056=((IkReal(1.00000000000000))*(cj5));
13977 IkReal x3057=((cj8)*(r10));
13978 IkReal x3058=((sj5)*(x3049));
13979 IkReal x3059=((sj5)*(x3048));
13980 IkReal x3060=((r11)*(sj3)*(sj8));
13981 IkReal x3061=((cj3)*(cj8)*(r00));
13982 IkReal x3062=((cj3)*(r01)*(sj8));
13983 IkReal x3063=((x3048)*(x3056));
13984 evalcond[0]=((x3058)+(((IkReal(-1.00000000000000))*(x3063)))+(((cj7)*(x3055)))+(((IkReal(-1.00000000000000))*(x3050)*(x3051)))+(((IkReal(-1.00000000000000))*(r22)*(x3053))));
13985 evalcond[1]=((((IkReal(-1.00000000000000))*(x3059)))+(((IkReal(-1.00000000000000))*(x3051)*(x3053)))+(((sj7)*(x3055)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x3049)*(x3056))));
13986 evalcond[2]=((((cj7)*(x3061)))+(x3059)+(((IkReal(-1.00000000000000))*(x3050)*(x3060)))+(((IkReal(-1.00000000000000))*(x3050)*(x3062)))+(((cj5)*(x3049)))+(((r12)*(x3054)))+(((cj7)*(sj3)*(x3057)))+(((sj7)*(x3052))));
13987 evalcond[3]=((x3058)+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3050)))+(((IkReal(-1.00000000000000))*(x3063)))+(((IkReal(-1.00000000000000))*(x3053)*(x3060)))+(((IkReal(-1.00000000000000))*(x3053)*(x3062)))+(((x3054)*(x3057)))+(((IkReal(-1.00000000000000))*(x3050)*(x3052)))+(((sj7)*(x3061))));
13988 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
13989 {
13990 continue;
13991 }
13992 }
13993 
13994 {
13995 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13996 vinfos[0].jointtype = 1;
13997 vinfos[0].foffset = j3;
13998 vinfos[0].indices[0] = _ij3[0];
13999 vinfos[0].indices[1] = _ij3[1];
14000 vinfos[0].maxsolutions = _nj3;
14001 vinfos[1].jointtype = 1;
14002 vinfos[1].foffset = j4;
14003 vinfos[1].indices[0] = _ij4[0];
14004 vinfos[1].indices[1] = _ij4[1];
14005 vinfos[1].maxsolutions = _nj4;
14006 vinfos[2].jointtype = 1;
14007 vinfos[2].foffset = j5;
14008 vinfos[2].indices[0] = _ij5[0];
14009 vinfos[2].indices[1] = _ij5[1];
14010 vinfos[2].maxsolutions = _nj5;
14011 vinfos[3].jointtype = 1;
14012 vinfos[3].foffset = j6;
14013 vinfos[3].indices[0] = _ij6[0];
14014 vinfos[3].indices[1] = _ij6[1];
14015 vinfos[3].maxsolutions = _nj6;
14016 vinfos[4].jointtype = 1;
14017 vinfos[4].foffset = j7;
14018 vinfos[4].indices[0] = _ij7[0];
14019 vinfos[4].indices[1] = _ij7[1];
14020 vinfos[4].maxsolutions = _nj7;
14021 vinfos[5].jointtype = 1;
14022 vinfos[5].foffset = j8;
14023 vinfos[5].indices[0] = _ij8[0];
14024 vinfos[5].indices[1] = _ij8[1];
14025 vinfos[5].maxsolutions = _nj8;
14026 std::vector<int> vfree(0);
14027 solutions.AddSolution(vinfos,vfree);
14028 }
14029 }
14030 }
14031 
14032 }
14033 
14034 }
14035 
14036 } else
14037 {
14038 {
14039 IkReal j4array[1], cj4array[1], sj4array[1];
14040 bool j4valid[1]={false};
14041 _nj4 = 1;
14042 IkReal x3064=((cj7)*(sj5));
14043 IkReal x3065=((r21)*(sj8));
14044 IkReal x3066=((cj5)*(cj7));
14045 IkReal x3067=((cj8)*(r20));
14046 IkReal x3068=((sj5)*(sj7));
14047 IkReal x3069=((IkReal(1.00000000000000))*(cj5)*(sj7));
14048 if( IKabs(((gconst62)*(((((r22)*(x3066)))+(((r22)*(x3068)))+(((IkReal(-1.00000000000000))*(x3067)*(x3069)))+(((x3064)*(x3067)))+(((IkReal(-1.00000000000000))*(x3064)*(x3065)))+(((cj5)*(sj7)*(x3065))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst62)*(((((IkReal(-1.00000000000000))*(r22)*(x3069)))+(((r22)*(x3064)))+(((IkReal(-1.00000000000000))*(x3067)*(x3068)))+(((x3065)*(x3066)))+(((x3065)*(x3068)))+(((IkReal(-1.00000000000000))*(x3066)*(x3067))))))) < IKFAST_ATAN2_MAGTHRESH )
14049  continue;
14050 j4array[0]=IKatan2(((gconst62)*(((((r22)*(x3066)))+(((r22)*(x3068)))+(((IkReal(-1.00000000000000))*(x3067)*(x3069)))+(((x3064)*(x3067)))+(((IkReal(-1.00000000000000))*(x3064)*(x3065)))+(((cj5)*(sj7)*(x3065)))))), ((gconst62)*(((((IkReal(-1.00000000000000))*(r22)*(x3069)))+(((r22)*(x3064)))+(((IkReal(-1.00000000000000))*(x3067)*(x3068)))+(((x3065)*(x3066)))+(((x3065)*(x3068)))+(((IkReal(-1.00000000000000))*(x3066)*(x3067)))))));
14051 sj4array[0]=IKsin(j4array[0]);
14052 cj4array[0]=IKcos(j4array[0]);
14053 if( j4array[0] > IKPI )
14054 {
14055  j4array[0]-=IK2PI;
14056 }
14057 else if( j4array[0] < -IKPI )
14058 { j4array[0]+=IK2PI;
14059 }
14060 j4valid[0] = true;
14061 for(int ij4 = 0; ij4 < 1; ++ij4)
14062 {
14063 if( !j4valid[ij4] )
14064 {
14065  continue;
14066 }
14067 _ij4[0] = ij4; _ij4[1] = -1;
14068 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14069 {
14070 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14071 {
14072  j4valid[iij4]=false; _ij4[1] = iij4; break;
14073 }
14074 }
14075 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14076 {
14077 IkReal evalcond[4];
14078 IkReal x3070=IKcos(j4);
14079 IkReal x3071=IKsin(j4);
14080 IkReal x3072=((IkReal(1.00000000000000))*(cj7));
14081 IkReal x3073=((cj8)*(r20));
14082 IkReal x3074=((cj3)*(r02));
14083 IkReal x3075=((IkReal(1.00000000000000))*(sj7));
14084 IkReal x3076=((sj3)*(sj7));
14085 IkReal x3077=((r21)*(sj8));
14086 IkReal x3078=((IkReal(1.00000000000000))*(cj5));
14087 IkReal x3079=((cj8)*(r10));
14088 IkReal x3080=((sj5)*(x3071));
14089 IkReal x3081=((sj5)*(x3070));
14090 IkReal x3082=((r11)*(sj3)*(sj8));
14091 IkReal x3083=((cj3)*(cj8)*(r00));
14092 IkReal x3084=((cj3)*(r01)*(sj8));
14093 IkReal x3085=((x3070)*(x3078));
14094 evalcond[0]=((((IkReal(-1.00000000000000))*(x3085)))+(((IkReal(-1.00000000000000))*(x3072)*(x3073)))+(((IkReal(-1.00000000000000))*(r22)*(x3075)))+(x3080)+(((cj7)*(x3077))));
14095 evalcond[1]=((((sj7)*(x3077)))+(((IkReal(-1.00000000000000))*(x3073)*(x3075)))+(((IkReal(-1.00000000000000))*(x3081)))+(((IkReal(-1.00000000000000))*(x3071)*(x3078)))+(((cj7)*(r22))));
14096 evalcond[2]=((x3081)+(((sj7)*(x3074)))+(((cj7)*(sj3)*(x3079)))+(((cj5)*(x3071)))+(((r12)*(x3076)))+(((IkReal(-1.00000000000000))*(x3072)*(x3084)))+(((IkReal(-1.00000000000000))*(x3072)*(x3082)))+(((cj7)*(x3083))));
14097 evalcond[3]=((((IkReal(-1.00000000000000))*(x3085)))+(((IkReal(-1.00000000000000))*(x3072)*(x3074)))+(x3080)+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3072)))+(((x3076)*(x3079)))+(((IkReal(-1.00000000000000))*(x3075)*(x3082)))+(((IkReal(-1.00000000000000))*(x3075)*(x3084)))+(((sj7)*(x3083))));
14098 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
14099 {
14100 continue;
14101 }
14102 }
14103 
14104 {
14105 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14106 vinfos[0].jointtype = 1;
14107 vinfos[0].foffset = j3;
14108 vinfos[0].indices[0] = _ij3[0];
14109 vinfos[0].indices[1] = _ij3[1];
14110 vinfos[0].maxsolutions = _nj3;
14111 vinfos[1].jointtype = 1;
14112 vinfos[1].foffset = j4;
14113 vinfos[1].indices[0] = _ij4[0];
14114 vinfos[1].indices[1] = _ij4[1];
14115 vinfos[1].maxsolutions = _nj4;
14116 vinfos[2].jointtype = 1;
14117 vinfos[2].foffset = j5;
14118 vinfos[2].indices[0] = _ij5[0];
14119 vinfos[2].indices[1] = _ij5[1];
14120 vinfos[2].maxsolutions = _nj5;
14121 vinfos[3].jointtype = 1;
14122 vinfos[3].foffset = j6;
14123 vinfos[3].indices[0] = _ij6[0];
14124 vinfos[3].indices[1] = _ij6[1];
14125 vinfos[3].maxsolutions = _nj6;
14126 vinfos[4].jointtype = 1;
14127 vinfos[4].foffset = j7;
14128 vinfos[4].indices[0] = _ij7[0];
14129 vinfos[4].indices[1] = _ij7[1];
14130 vinfos[4].maxsolutions = _nj7;
14131 vinfos[5].jointtype = 1;
14132 vinfos[5].foffset = j8;
14133 vinfos[5].indices[0] = _ij8[0];
14134 vinfos[5].indices[1] = _ij8[1];
14135 vinfos[5].maxsolutions = _nj8;
14136 std::vector<int> vfree(0);
14137 solutions.AddSolution(vinfos,vfree);
14138 }
14139 }
14140 }
14141 
14142 }
14143 
14144 }
14145 }
14146 }
14147 
14148 } else
14149 {
14150 if( 1 )
14151 {
14152 continue;
14153 
14154 } else
14155 {
14156 }
14157 }
14158 }
14159 }
14160 }
14161 }
14162 
14163 } else
14164 {
14165 {
14166 IkReal j5array[1], cj5array[1], sj5array[1];
14167 bool j5valid[1]={false};
14168 _nj5 = 1;
14169 IkReal x3086=((IkReal(4.00000000000000))*(cj7));
14170 IkReal x3087=((cj8)*(npx));
14171 IkReal x3088=((IkReal(4.00000000000000))*(sj7));
14172 IkReal x3089=((IkReal(4.00000000000000))*(npy)*(sj8));
14173 if( IKabs(((((IKabs(cj6) != 0)?((IkReal)1/(cj6)):(IkReal)1.0e30))*(((((IkReal(0.360000000000000))*(sj7)))+(((npy)*(sj8)*(x3088)))+(((IkReal(-0.380000000000000))*(sj6)))+(((npz)*(x3086)))+(((IkReal(0.120000000000000))*(cj6)))+(((IkReal(-1.00000000000000))*(x3087)*(x3088))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((npz)*(x3088)))+(((IkReal(-1.00000000000000))*(npy)*(sj8)*(x3086)))+(((x3086)*(x3087)))+(((IkReal(-0.360000000000000))*(cj7))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj6) != 0)?((IkReal)1/(cj6)):(IkReal)1.0e30))*(((((IkReal(0.360000000000000))*(sj7)))+(((npy)*(sj8)*(x3088)))+(((IkReal(-0.380000000000000))*(sj6)))+(((npz)*(x3086)))+(((IkReal(0.120000000000000))*(cj6)))+(((IkReal(-1.00000000000000))*(x3087)*(x3088)))))))+IKsqr(((IkReal(-0.940000000000000))+(((npz)*(x3088)))+(((IkReal(-1.00000000000000))*(npy)*(sj8)*(x3086)))+(((x3086)*(x3087)))+(((IkReal(-0.360000000000000))*(cj7)))))-1) <= IKFAST_SINCOS_THRESH )
14174  continue;
14175 j5array[0]=IKatan2(((((IKabs(cj6) != 0)?((IkReal)1/(cj6)):(IkReal)1.0e30))*(((((IkReal(0.360000000000000))*(sj7)))+(((npy)*(sj8)*(x3088)))+(((IkReal(-0.380000000000000))*(sj6)))+(((npz)*(x3086)))+(((IkReal(0.120000000000000))*(cj6)))+(((IkReal(-1.00000000000000))*(x3087)*(x3088)))))), ((IkReal(-0.940000000000000))+(((npz)*(x3088)))+(((IkReal(-1.00000000000000))*(npy)*(sj8)*(x3086)))+(((x3086)*(x3087)))+(((IkReal(-0.360000000000000))*(cj7)))));
14176 sj5array[0]=IKsin(j5array[0]);
14177 cj5array[0]=IKcos(j5array[0]);
14178 if( j5array[0] > IKPI )
14179 {
14180  j5array[0]-=IK2PI;
14181 }
14182 else if( j5array[0] < -IKPI )
14183 { j5array[0]+=IK2PI;
14184 }
14185 j5valid[0] = true;
14186 for(int ij5 = 0; ij5 < 1; ++ij5)
14187 {
14188 if( !j5valid[ij5] )
14189 {
14190  continue;
14191 }
14192 _ij5[0] = ij5; _ij5[1] = -1;
14193 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
14194 {
14195 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14196 {
14197  j5valid[iij5]=false; _ij5[1] = iij5; break;
14198 }
14199 }
14200 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14201 {
14202 IkReal evalcond[3];
14203 IkReal x3090=IKsin(j5);
14204 IkReal x3091=((IkReal(1.00000000000000))*(sj7));
14205 IkReal x3092=((npy)*(sj8));
14206 IkReal x3093=((cj8)*(npx));
14207 IkReal x3094=((IkReal(0.250000000000000))*(x3090));
14208 evalcond[0]=((((IkReal(-0.0300000000000000))*(sj6)))+(((IkReal(-0.0950000000000000))*(cj6)))+(((npx)*(sj8)))+(((sj6)*(x3094)))+(((cj8)*(npy))));
14209 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x3091)))+(((IkReal(-1.00000000000000))*(cj7)*(x3093)))+(((cj7)*(x3092)))+(((IkReal(0.250000000000000))*(IKcos(j5)))));
14210 evalcond[2]=((((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x3092)))+(((IkReal(0.0300000000000000))*(cj6)))+(((IkReal(-0.0950000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(x3091)*(x3093)))+(((IkReal(-1.00000000000000))*(cj6)*(x3094)))+(((cj7)*(npz))));
14211 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
14212 {
14213 continue;
14214 }
14215 }
14216 
14217 {
14218 IkReal dummyeval[1];
14219 IkReal gconst46;
14220 gconst46=IKsign(((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5))))));
14221 dummyeval[0]=((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5)))));
14222 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14223 {
14224 {
14225 IkReal dummyeval[1];
14226 IkReal gconst47;
14227 gconst47=IKsign(((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5))))));
14228 dummyeval[0]=((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5)))));
14229 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14230 {
14231 {
14232 IkReal evalcond[9];
14233 IkReal x3095=((IkReal(1.00000000000000))*(sj7));
14234 IkReal x3096=((IkReal(1.00000000000000))*(cj3));
14235 IkReal x3097=((cj7)*(r02));
14236 IkReal x3098=((cj8)*(r00));
14237 IkReal x3099=((cj3)*(sj7));
14238 IkReal x3100=((cj8)*(npx));
14239 IkReal x3101=((r01)*(sj3));
14240 IkReal x3102=((cj7)*(sj8));
14241 IkReal x3103=((r11)*(sj8));
14242 IkReal x3104=((IkReal(1.00000000000000))*(cj7));
14243 IkReal x3105=((sj7)*(sj8));
14244 IkReal x3106=((cj8)*(r10));
14245 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
14246 evalcond[1]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(sj5))));
14247 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x3095)))+(((IkReal(-1.00000000000000))*(x3100)*(x3104)))+(((npy)*(x3102))));
14248 evalcond[3]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x3096)))+(((cj8)*(x3101)))+(((r00)*(sj3)*(sj8)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x3096))));
14249 evalcond[4]=((((r21)*(x3105)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x3095)))+(((cj7)*(r22))));
14250 evalcond[5]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x3095)*(x3100)))+(((npy)*(x3105)))+(((cj7)*(npz))));
14251 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(x3096)*(x3102)))+(((cj3)*(cj7)*(x3106)))+(((IkReal(-1.00000000000000))*(sj3)*(x3098)*(x3104)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x3095)))+(((x3101)*(x3102)))+(((r12)*(x3099))));
14252 evalcond[7]=((IkReal(1.00000000000000))+(((x3099)*(x3106)))+(((sj3)*(x3097)))+(((IkReal(-1.00000000000000))*(sj3)*(x3095)*(x3098)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x3096)))+(((IkReal(-1.00000000000000))*(cj3)*(x3095)*(x3103)))+(((x3101)*(x3105))));
14253 evalcond[8]=((((x3098)*(x3099)))+(((IkReal(-1.00000000000000))*(sj3)*(x3095)*(x3103)))+(((sj3)*(sj7)*(x3106)))+(((IkReal(-1.00000000000000))*(x3096)*(x3097)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x3095)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3104))));
14254 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
14255 {
14256 {
14257 IkReal dummyeval[1];
14258 IkReal gconst48;
14259 gconst48=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
14260 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
14261 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14262 {
14263 {
14264 IkReal dummyeval[1];
14265 IkReal gconst49;
14266 gconst49=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
14267 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
14268 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14269 {
14270 continue;
14271 
14272 } else
14273 {
14274 {
14275 IkReal j4array[1], cj4array[1], sj4array[1];
14276 bool j4valid[1]={false};
14277 _nj4 = 1;
14278 IkReal x3107=((cj8)*(sj5));
14279 IkReal x3108=((cj3)*(r01));
14280 IkReal x3109=((IkReal(1.00000000000000))*(cj5));
14281 IkReal x3110=((r11)*(sj3));
14282 IkReal x3111=((sj5)*(sj8));
14283 IkReal x3112=((r10)*(sj3));
14284 IkReal x3113=((cj3)*(r00)*(sj8));
14285 if( IKabs(((gconst49)*(((((x3107)*(x3108)))+(((cj5)*(r20)*(sj8)))+(((x3107)*(x3110)))+(((x3111)*(x3112)))+(((cj3)*(r00)*(x3111)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((IkReal(-1.00000000000000))*(sj8)*(x3109)*(x3112)))+(((IkReal(-1.00000000000000))*(cj8)*(x3108)*(x3109)))+(((IkReal(-1.00000000000000))*(cj8)*(x3109)*(x3110)))+(((IkReal(-1.00000000000000))*(x3109)*(x3113)))+(((r21)*(x3107)))+(((r20)*(x3111))))))) < IKFAST_ATAN2_MAGTHRESH )
14286  continue;
14287 j4array[0]=IKatan2(((gconst49)*(((((x3107)*(x3108)))+(((cj5)*(r20)*(sj8)))+(((x3107)*(x3110)))+(((x3111)*(x3112)))+(((cj3)*(r00)*(x3111)))+(((cj5)*(cj8)*(r21)))))), ((gconst49)*(((((IkReal(-1.00000000000000))*(sj8)*(x3109)*(x3112)))+(((IkReal(-1.00000000000000))*(cj8)*(x3108)*(x3109)))+(((IkReal(-1.00000000000000))*(cj8)*(x3109)*(x3110)))+(((IkReal(-1.00000000000000))*(x3109)*(x3113)))+(((r21)*(x3107)))+(((r20)*(x3111)))))));
14288 sj4array[0]=IKsin(j4array[0]);
14289 cj4array[0]=IKcos(j4array[0]);
14290 if( j4array[0] > IKPI )
14291 {
14292  j4array[0]-=IK2PI;
14293 }
14294 else if( j4array[0] < -IKPI )
14295 { j4array[0]+=IK2PI;
14296 }
14297 j4valid[0] = true;
14298 for(int ij4 = 0; ij4 < 1; ++ij4)
14299 {
14300 if( !j4valid[ij4] )
14301 {
14302  continue;
14303 }
14304 _ij4[0] = ij4; _ij4[1] = -1;
14305 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14306 {
14307 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14308 {
14309  j4valid[iij4]=false; _ij4[1] = iij4; break;
14310 }
14311 }
14312 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14313 {
14314 IkReal evalcond[4];
14315 IkReal x3114=IKsin(j4);
14316 IkReal x3115=IKcos(j4);
14317 IkReal x3116=((IkReal(1.00000000000000))*(cj8));
14318 IkReal x3117=((cj3)*(r01));
14319 IkReal x3118=((cj3)*(r00));
14320 IkReal x3119=((cj7)*(cj8));
14321 IkReal x3120=((IkReal(1.00000000000000))*(cj5));
14322 IkReal x3121=((IkReal(1.00000000000000))*(sj8));
14323 IkReal x3122=((r11)*(sj3));
14324 IkReal x3123=((r10)*(sj3));
14325 IkReal x3124=((sj5)*(x3114));
14326 IkReal x3125=((sj5)*(x3115));
14327 IkReal x3126=((x3115)*(x3120));
14328 evalcond[0]=((((IkReal(-1.00000000000000))*(x3114)*(x3120)))+(((IkReal(-1.00000000000000))*(x3125)))+(((cj8)*(r21)))+(((r20)*(sj8))));
14329 evalcond[1]=((x3124)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3116)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x3126)))+(((cj7)*(r21)*(sj8))));
14330 evalcond[2]=((x3124)+(((IkReal(-1.00000000000000))*(x3116)*(x3122)))+(((IkReal(-1.00000000000000))*(x3121)*(x3123)))+(((IkReal(-1.00000000000000))*(x3126)))+(((IkReal(-1.00000000000000))*(x3118)*(x3121)))+(((IkReal(-1.00000000000000))*(x3116)*(x3117))));
14331 evalcond[3]=((((r12)*(sj3)*(sj7)))+(x3125)+(((x3118)*(x3119)))+(((x3119)*(x3123)))+(((cj3)*(r02)*(sj7)))+(((cj5)*(x3114)))+(((IkReal(-1.00000000000000))*(cj7)*(x3121)*(x3122)))+(((IkReal(-1.00000000000000))*(cj7)*(x3117)*(x3121))));
14332 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
14333 {
14334 continue;
14335 }
14336 }
14337 
14338 {
14339 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14340 vinfos[0].jointtype = 1;
14341 vinfos[0].foffset = j3;
14342 vinfos[0].indices[0] = _ij3[0];
14343 vinfos[0].indices[1] = _ij3[1];
14344 vinfos[0].maxsolutions = _nj3;
14345 vinfos[1].jointtype = 1;
14346 vinfos[1].foffset = j4;
14347 vinfos[1].indices[0] = _ij4[0];
14348 vinfos[1].indices[1] = _ij4[1];
14349 vinfos[1].maxsolutions = _nj4;
14350 vinfos[2].jointtype = 1;
14351 vinfos[2].foffset = j5;
14352 vinfos[2].indices[0] = _ij5[0];
14353 vinfos[2].indices[1] = _ij5[1];
14354 vinfos[2].maxsolutions = _nj5;
14355 vinfos[3].jointtype = 1;
14356 vinfos[3].foffset = j6;
14357 vinfos[3].indices[0] = _ij6[0];
14358 vinfos[3].indices[1] = _ij6[1];
14359 vinfos[3].maxsolutions = _nj6;
14360 vinfos[4].jointtype = 1;
14361 vinfos[4].foffset = j7;
14362 vinfos[4].indices[0] = _ij7[0];
14363 vinfos[4].indices[1] = _ij7[1];
14364 vinfos[4].maxsolutions = _nj7;
14365 vinfos[5].jointtype = 1;
14366 vinfos[5].foffset = j8;
14367 vinfos[5].indices[0] = _ij8[0];
14368 vinfos[5].indices[1] = _ij8[1];
14369 vinfos[5].maxsolutions = _nj8;
14370 std::vector<int> vfree(0);
14371 solutions.AddSolution(vinfos,vfree);
14372 }
14373 }
14374 }
14375 
14376 }
14377 
14378 }
14379 
14380 } else
14381 {
14382 {
14383 IkReal j4array[1], cj4array[1], sj4array[1];
14384 bool j4valid[1]={false};
14385 _nj4 = 1;
14386 IkReal x3127=((sj5)*(sj8));
14387 IkReal x3128=((IkReal(1.00000000000000))*(cj7));
14388 IkReal x3129=((r22)*(sj7));
14389 IkReal x3130=((cj8)*(sj5));
14390 IkReal x3131=((cj5)*(cj8));
14391 IkReal x3132=((cj5)*(sj8));
14392 if( IKabs(((gconst48)*(((((r20)*(x3132)))+(((r21)*(x3131)))+(((IkReal(-1.00000000000000))*(r21)*(x3127)*(x3128)))+(((sj5)*(x3129)))+(((cj7)*(r20)*(x3130))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((r20)*(x3127)))+(((r21)*(x3130)))+(((cj7)*(r21)*(x3132)))+(((IkReal(-1.00000000000000))*(cj5)*(x3129)))+(((IkReal(-1.00000000000000))*(r20)*(x3128)*(x3131))))))) < IKFAST_ATAN2_MAGTHRESH )
14393  continue;
14394 j4array[0]=IKatan2(((gconst48)*(((((r20)*(x3132)))+(((r21)*(x3131)))+(((IkReal(-1.00000000000000))*(r21)*(x3127)*(x3128)))+(((sj5)*(x3129)))+(((cj7)*(r20)*(x3130)))))), ((gconst48)*(((((r20)*(x3127)))+(((r21)*(x3130)))+(((cj7)*(r21)*(x3132)))+(((IkReal(-1.00000000000000))*(cj5)*(x3129)))+(((IkReal(-1.00000000000000))*(r20)*(x3128)*(x3131)))))));
14395 sj4array[0]=IKsin(j4array[0]);
14396 cj4array[0]=IKcos(j4array[0]);
14397 if( j4array[0] > IKPI )
14398 {
14399  j4array[0]-=IK2PI;
14400 }
14401 else if( j4array[0] < -IKPI )
14402 { j4array[0]+=IK2PI;
14403 }
14404 j4valid[0] = true;
14405 for(int ij4 = 0; ij4 < 1; ++ij4)
14406 {
14407 if( !j4valid[ij4] )
14408 {
14409  continue;
14410 }
14411 _ij4[0] = ij4; _ij4[1] = -1;
14412 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14413 {
14414 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14415 {
14416  j4valid[iij4]=false; _ij4[1] = iij4; break;
14417 }
14418 }
14419 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14420 {
14421 IkReal evalcond[4];
14422 IkReal x3133=IKsin(j4);
14423 IkReal x3134=IKcos(j4);
14424 IkReal x3135=((IkReal(1.00000000000000))*(cj8));
14425 IkReal x3136=((cj3)*(r01));
14426 IkReal x3137=((cj3)*(r00));
14427 IkReal x3138=((cj7)*(cj8));
14428 IkReal x3139=((IkReal(1.00000000000000))*(cj5));
14429 IkReal x3140=((IkReal(1.00000000000000))*(sj8));
14430 IkReal x3141=((r11)*(sj3));
14431 IkReal x3142=((r10)*(sj3));
14432 IkReal x3143=((sj5)*(x3133));
14433 IkReal x3144=((sj5)*(x3134));
14434 IkReal x3145=((x3134)*(x3139));
14435 evalcond[0]=((((IkReal(-1.00000000000000))*(x3144)))+(((IkReal(-1.00000000000000))*(x3133)*(x3139)))+(((cj8)*(r21)))+(((r20)*(sj8))));
14436 evalcond[1]=((x3143)+(((IkReal(-1.00000000000000))*(x3145)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3135)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
14437 evalcond[2]=((x3143)+(((IkReal(-1.00000000000000))*(x3145)))+(((IkReal(-1.00000000000000))*(x3140)*(x3142)))+(((IkReal(-1.00000000000000))*(x3135)*(x3141)))+(((IkReal(-1.00000000000000))*(x3135)*(x3136)))+(((IkReal(-1.00000000000000))*(x3137)*(x3140))));
14438 evalcond[3]=((((r12)*(sj3)*(sj7)))+(x3144)+(((IkReal(-1.00000000000000))*(cj7)*(x3140)*(x3141)))+(((x3137)*(x3138)))+(((cj5)*(x3133)))+(((cj3)*(r02)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x3136)*(x3140)))+(((x3138)*(x3142))));
14439 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
14440 {
14441 continue;
14442 }
14443 }
14444 
14445 {
14446 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14447 vinfos[0].jointtype = 1;
14448 vinfos[0].foffset = j3;
14449 vinfos[0].indices[0] = _ij3[0];
14450 vinfos[0].indices[1] = _ij3[1];
14451 vinfos[0].maxsolutions = _nj3;
14452 vinfos[1].jointtype = 1;
14453 vinfos[1].foffset = j4;
14454 vinfos[1].indices[0] = _ij4[0];
14455 vinfos[1].indices[1] = _ij4[1];
14456 vinfos[1].maxsolutions = _nj4;
14457 vinfos[2].jointtype = 1;
14458 vinfos[2].foffset = j5;
14459 vinfos[2].indices[0] = _ij5[0];
14460 vinfos[2].indices[1] = _ij5[1];
14461 vinfos[2].maxsolutions = _nj5;
14462 vinfos[3].jointtype = 1;
14463 vinfos[3].foffset = j6;
14464 vinfos[3].indices[0] = _ij6[0];
14465 vinfos[3].indices[1] = _ij6[1];
14466 vinfos[3].maxsolutions = _nj6;
14467 vinfos[4].jointtype = 1;
14468 vinfos[4].foffset = j7;
14469 vinfos[4].indices[0] = _ij7[0];
14470 vinfos[4].indices[1] = _ij7[1];
14471 vinfos[4].maxsolutions = _nj7;
14472 vinfos[5].jointtype = 1;
14473 vinfos[5].foffset = j8;
14474 vinfos[5].indices[0] = _ij8[0];
14475 vinfos[5].indices[1] = _ij8[1];
14476 vinfos[5].maxsolutions = _nj8;
14477 std::vector<int> vfree(0);
14478 solutions.AddSolution(vinfos,vfree);
14479 }
14480 }
14481 }
14482 
14483 }
14484 
14485 }
14486 
14487 } else
14488 {
14489 IkReal x3146=((IkReal(1.00000000000000))*(sj7));
14490 IkReal x3147=((IkReal(1.00000000000000))*(cj3));
14491 IkReal x3148=((cj7)*(r02));
14492 IkReal x3149=((cj8)*(r00));
14493 IkReal x3150=((cj3)*(sj7));
14494 IkReal x3151=((cj8)*(npx));
14495 IkReal x3152=((r01)*(sj3));
14496 IkReal x3153=((cj7)*(sj8));
14497 IkReal x3154=((r11)*(sj8));
14498 IkReal x3155=((IkReal(1.00000000000000))*(cj7));
14499 IkReal x3156=((sj7)*(sj8));
14500 IkReal x3157=((cj8)*(r10));
14501 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
14502 evalcond[1]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(sj5))));
14503 evalcond[2]=((IkReal(0.235000000000000))+(((npy)*(x3153)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x3146)))+(((IkReal(-1.00000000000000))*(x3151)*(x3155))));
14504 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj8)*(x3147)))+(((r00)*(sj3)*(sj8)))+(((cj8)*(x3152)))+(((IkReal(-1.00000000000000))*(cj8)*(r11)*(x3147))));
14505 evalcond[4]=((((IkReal(-1.00000000000000))*(cj8)*(r20)*(x3146)))+(((cj7)*(r22)))+(((r21)*(x3156))));
14506 evalcond[5]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x3146)*(x3151)))+(((npy)*(x3156)))+(((cj7)*(npz))));
14507 evalcond[6]=((((r12)*(x3150)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x3146)))+(((IkReal(-1.00000000000000))*(r11)*(x3147)*(x3153)))+(((IkReal(-1.00000000000000))*(sj3)*(x3149)*(x3155)))+(((x3152)*(x3153)))+(((cj3)*(cj7)*(x3157))));
14508 evalcond[7]=((IkReal(-1.00000000000000))+(((sj3)*(x3148)))+(((x3150)*(x3157)))+(((IkReal(-1.00000000000000))*(sj3)*(x3146)*(x3149)))+(((IkReal(-1.00000000000000))*(cj3)*(x3146)*(x3154)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x3147)))+(((x3152)*(x3156))));
14509 evalcond[8]=((((x3149)*(x3150)))+(((IkReal(-1.00000000000000))*(x3147)*(x3148)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x3146)))+(((sj3)*(sj7)*(x3157)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3155)))+(((IkReal(-1.00000000000000))*(sj3)*(x3146)*(x3154))));
14510 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
14511 {
14512 {
14513 IkReal dummyeval[1];
14514 IkReal gconst50;
14515 gconst50=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
14516 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
14517 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14518 {
14519 {
14520 IkReal dummyeval[1];
14521 IkReal gconst51;
14522 gconst51=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
14523 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
14524 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14525 {
14526 continue;
14527 
14528 } else
14529 {
14530 {
14531 IkReal j4array[1], cj4array[1], sj4array[1];
14532 bool j4valid[1]={false};
14533 _nj4 = 1;
14534 IkReal x3158=((IkReal(1.00000000000000))*(sj5));
14535 IkReal x3159=((r20)*(sj8));
14536 IkReal x3160=((cj5)*(cj8));
14537 IkReal x3161=((r11)*(sj3));
14538 IkReal x3162=((cj3)*(r01));
14539 IkReal x3163=((cj3)*(r00)*(sj8));
14540 IkReal x3164=((r10)*(sj3)*(sj8));
14541 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x3158)*(x3163)))+(((IkReal(-1.00000000000000))*(x3158)*(x3164)))+(((IkReal(-1.00000000000000))*(r21)*(x3160)))+(((IkReal(-1.00000000000000))*(cj8)*(x3158)*(x3162)))+(((IkReal(-1.00000000000000))*(cj8)*(x3158)*(x3161)))+(((IkReal(-1.00000000000000))*(cj5)*(x3159))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x3158)*(x3159)))+(((cj5)*(x3164)))+(((cj5)*(x3163)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x3158)))+(((x3160)*(x3161)))+(((x3160)*(x3162))))))) < IKFAST_ATAN2_MAGTHRESH )
14542  continue;
14543 j4array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(x3158)*(x3163)))+(((IkReal(-1.00000000000000))*(x3158)*(x3164)))+(((IkReal(-1.00000000000000))*(r21)*(x3160)))+(((IkReal(-1.00000000000000))*(cj8)*(x3158)*(x3162)))+(((IkReal(-1.00000000000000))*(cj8)*(x3158)*(x3161)))+(((IkReal(-1.00000000000000))*(cj5)*(x3159)))))), ((gconst51)*(((((IkReal(-1.00000000000000))*(x3158)*(x3159)))+(((cj5)*(x3164)))+(((cj5)*(x3163)))+(((IkReal(-1.00000000000000))*(cj8)*(r21)*(x3158)))+(((x3160)*(x3161)))+(((x3160)*(x3162)))))));
14544 sj4array[0]=IKsin(j4array[0]);
14545 cj4array[0]=IKcos(j4array[0]);
14546 if( j4array[0] > IKPI )
14547 {
14548  j4array[0]-=IK2PI;
14549 }
14550 else if( j4array[0] < -IKPI )
14551 { j4array[0]+=IK2PI;
14552 }
14553 j4valid[0] = true;
14554 for(int ij4 = 0; ij4 < 1; ++ij4)
14555 {
14556 if( !j4valid[ij4] )
14557 {
14558  continue;
14559 }
14560 _ij4[0] = ij4; _ij4[1] = -1;
14561 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14562 {
14563 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14564 {
14565  j4valid[iij4]=false; _ij4[1] = iij4; break;
14566 }
14567 }
14568 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14569 {
14570 IkReal evalcond[4];
14571 IkReal x3165=IKsin(j4);
14572 IkReal x3166=IKcos(j4);
14573 IkReal x3167=((IkReal(1.00000000000000))*(cj8));
14574 IkReal x3168=((cj3)*(r01));
14575 IkReal x3169=((cj3)*(r00));
14576 IkReal x3170=((cj7)*(cj8));
14577 IkReal x3171=((r11)*(sj3));
14578 IkReal x3172=((IkReal(1.00000000000000))*(sj8));
14579 IkReal x3173=((r10)*(sj3));
14580 IkReal x3174=((sj5)*(x3166));
14581 IkReal x3175=((cj5)*(x3165));
14582 IkReal x3176=((cj5)*(x3166));
14583 IkReal x3177=((sj5)*(x3165));
14584 IkReal x3178=((x3175)+(x3174));
14585 evalcond[0]=((x3178)+(((cj8)*(r21)))+(((r20)*(sj8))));
14586 evalcond[1]=((x3177)+(((IkReal(-1.00000000000000))*(x3176)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3167)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
14587 evalcond[2]=((((IkReal(-1.00000000000000))*(x3169)*(x3172)))+(x3176)+(((IkReal(-1.00000000000000))*(x3167)*(x3168)))+(((IkReal(-1.00000000000000))*(x3177)))+(((IkReal(-1.00000000000000))*(x3167)*(x3171)))+(((IkReal(-1.00000000000000))*(x3172)*(x3173))));
14588 evalcond[3]=((((r12)*(sj3)*(sj7)))+(x3178)+(((IkReal(-1.00000000000000))*(cj7)*(x3171)*(x3172)))+(((x3170)*(x3173)))+(((cj3)*(r02)*(sj7)))+(((x3169)*(x3170)))+(((IkReal(-1.00000000000000))*(cj7)*(x3168)*(x3172))));
14589 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
14590 {
14591 continue;
14592 }
14593 }
14594 
14595 {
14596 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14597 vinfos[0].jointtype = 1;
14598 vinfos[0].foffset = j3;
14599 vinfos[0].indices[0] = _ij3[0];
14600 vinfos[0].indices[1] = _ij3[1];
14601 vinfos[0].maxsolutions = _nj3;
14602 vinfos[1].jointtype = 1;
14603 vinfos[1].foffset = j4;
14604 vinfos[1].indices[0] = _ij4[0];
14605 vinfos[1].indices[1] = _ij4[1];
14606 vinfos[1].maxsolutions = _nj4;
14607 vinfos[2].jointtype = 1;
14608 vinfos[2].foffset = j5;
14609 vinfos[2].indices[0] = _ij5[0];
14610 vinfos[2].indices[1] = _ij5[1];
14611 vinfos[2].maxsolutions = _nj5;
14612 vinfos[3].jointtype = 1;
14613 vinfos[3].foffset = j6;
14614 vinfos[3].indices[0] = _ij6[0];
14615 vinfos[3].indices[1] = _ij6[1];
14616 vinfos[3].maxsolutions = _nj6;
14617 vinfos[4].jointtype = 1;
14618 vinfos[4].foffset = j7;
14619 vinfos[4].indices[0] = _ij7[0];
14620 vinfos[4].indices[1] = _ij7[1];
14621 vinfos[4].maxsolutions = _nj7;
14622 vinfos[5].jointtype = 1;
14623 vinfos[5].foffset = j8;
14624 vinfos[5].indices[0] = _ij8[0];
14625 vinfos[5].indices[1] = _ij8[1];
14626 vinfos[5].maxsolutions = _nj8;
14627 std::vector<int> vfree(0);
14628 solutions.AddSolution(vinfos,vfree);
14629 }
14630 }
14631 }
14632 
14633 }
14634 
14635 }
14636 
14637 } else
14638 {
14639 {
14640 IkReal j4array[1], cj4array[1], sj4array[1];
14641 bool j4valid[1]={false};
14642 _nj4 = 1;
14643 IkReal x3179=((cj8)*(sj5));
14644 IkReal x3180=((sj5)*(sj8));
14645 IkReal x3181=((r22)*(sj7));
14646 IkReal x3182=((cj7)*(r20));
14647 IkReal x3183=((cj5)*(cj8));
14648 IkReal x3184=((cj7)*(r21));
14649 IkReal x3185=((cj5)*(sj8));
14650 if( IKabs(((gconst50)*(((((r20)*(x3185)))+(((x3180)*(x3184)))+(((IkReal(-1.00000000000000))*(sj5)*(x3181)))+(((IkReal(-1.00000000000000))*(x3179)*(x3182)))+(((r21)*(x3183))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((r20)*(x3180)))+(((x3182)*(x3183)))+(((r21)*(x3179)))+(((cj5)*(x3181)))+(((IkReal(-1.00000000000000))*(x3184)*(x3185))))))) < IKFAST_ATAN2_MAGTHRESH )
14651  continue;
14652 j4array[0]=IKatan2(((gconst50)*(((((r20)*(x3185)))+(((x3180)*(x3184)))+(((IkReal(-1.00000000000000))*(sj5)*(x3181)))+(((IkReal(-1.00000000000000))*(x3179)*(x3182)))+(((r21)*(x3183)))))), ((gconst50)*(((((r20)*(x3180)))+(((x3182)*(x3183)))+(((r21)*(x3179)))+(((cj5)*(x3181)))+(((IkReal(-1.00000000000000))*(x3184)*(x3185)))))));
14653 sj4array[0]=IKsin(j4array[0]);
14654 cj4array[0]=IKcos(j4array[0]);
14655 if( j4array[0] > IKPI )
14656 {
14657  j4array[0]-=IK2PI;
14658 }
14659 else if( j4array[0] < -IKPI )
14660 { j4array[0]+=IK2PI;
14661 }
14662 j4valid[0] = true;
14663 for(int ij4 = 0; ij4 < 1; ++ij4)
14664 {
14665 if( !j4valid[ij4] )
14666 {
14667  continue;
14668 }
14669 _ij4[0] = ij4; _ij4[1] = -1;
14670 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14671 {
14672 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14673 {
14674  j4valid[iij4]=false; _ij4[1] = iij4; break;
14675 }
14676 }
14677 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14678 {
14679 IkReal evalcond[4];
14680 IkReal x3186=IKsin(j4);
14681 IkReal x3187=IKcos(j4);
14682 IkReal x3188=((IkReal(1.00000000000000))*(cj8));
14683 IkReal x3189=((cj3)*(r01));
14684 IkReal x3190=((cj3)*(r00));
14685 IkReal x3191=((cj7)*(cj8));
14686 IkReal x3192=((r11)*(sj3));
14687 IkReal x3193=((IkReal(1.00000000000000))*(sj8));
14688 IkReal x3194=((r10)*(sj3));
14689 IkReal x3195=((sj5)*(x3187));
14690 IkReal x3196=((cj5)*(x3186));
14691 IkReal x3197=((cj5)*(x3187));
14692 IkReal x3198=((sj5)*(x3186));
14693 IkReal x3199=((x3196)+(x3195));
14694 evalcond[0]=((x3199)+(((cj8)*(r21)))+(((r20)*(sj8))));
14695 evalcond[1]=((x3198)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3188)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x3197)))+(((cj7)*(r21)*(sj8))));
14696 evalcond[2]=((((IkReal(-1.00000000000000))*(x3190)*(x3193)))+(x3197)+(((IkReal(-1.00000000000000))*(x3193)*(x3194)))+(((IkReal(-1.00000000000000))*(x3188)*(x3192)))+(((IkReal(-1.00000000000000))*(x3188)*(x3189)))+(((IkReal(-1.00000000000000))*(x3198))));
14697 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x3189)*(x3193)))+(x3199)+(((IkReal(-1.00000000000000))*(cj7)*(x3192)*(x3193)))+(((cj3)*(r02)*(sj7)))+(((x3190)*(x3191)))+(((x3191)*(x3194))));
14698 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
14699 {
14700 continue;
14701 }
14702 }
14703 
14704 {
14705 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14706 vinfos[0].jointtype = 1;
14707 vinfos[0].foffset = j3;
14708 vinfos[0].indices[0] = _ij3[0];
14709 vinfos[0].indices[1] = _ij3[1];
14710 vinfos[0].maxsolutions = _nj3;
14711 vinfos[1].jointtype = 1;
14712 vinfos[1].foffset = j4;
14713 vinfos[1].indices[0] = _ij4[0];
14714 vinfos[1].indices[1] = _ij4[1];
14715 vinfos[1].maxsolutions = _nj4;
14716 vinfos[2].jointtype = 1;
14717 vinfos[2].foffset = j5;
14718 vinfos[2].indices[0] = _ij5[0];
14719 vinfos[2].indices[1] = _ij5[1];
14720 vinfos[2].maxsolutions = _nj5;
14721 vinfos[3].jointtype = 1;
14722 vinfos[3].foffset = j6;
14723 vinfos[3].indices[0] = _ij6[0];
14724 vinfos[3].indices[1] = _ij6[1];
14725 vinfos[3].maxsolutions = _nj6;
14726 vinfos[4].jointtype = 1;
14727 vinfos[4].foffset = j7;
14728 vinfos[4].indices[0] = _ij7[0];
14729 vinfos[4].indices[1] = _ij7[1];
14730 vinfos[4].maxsolutions = _nj7;
14731 vinfos[5].jointtype = 1;
14732 vinfos[5].foffset = j8;
14733 vinfos[5].indices[0] = _ij8[0];
14734 vinfos[5].indices[1] = _ij8[1];
14735 vinfos[5].maxsolutions = _nj8;
14736 std::vector<int> vfree(0);
14737 solutions.AddSolution(vinfos,vfree);
14738 }
14739 }
14740 }
14741 
14742 }
14743 
14744 }
14745 
14746 } else
14747 {
14748 IkReal x3200=((cj3)*(cj8));
14749 IkReal x3201=((IkReal(1.00000000000000))*(sj7));
14750 IkReal x3202=((cj8)*(npx));
14751 IkReal x3203=((cj8)*(sj3));
14752 IkReal x3204=((npy)*(sj8));
14753 IkReal x3205=((r02)*(sj3));
14754 IkReal x3206=((IkReal(1.00000000000000))*(r11));
14755 IkReal x3207=((cj3)*(r12));
14756 IkReal x3208=((IkReal(1.00000000000000))*(cj7));
14757 IkReal x3209=((sj3)*(sj8));
14758 IkReal x3210=((IkReal(1.00000000000000))*(cj3)*(sj8));
14759 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
14760 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
14761 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
14762 evalcond[3]=((IkReal(0.235000000000000))+(((cj7)*(x3204)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(x3202)*(x3208)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x3201))));
14763 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x3210)))+(((IkReal(-1.00000000000000))*(x3200)*(x3206)))+(((r00)*(x3209)))+(((r01)*(x3203))));
14764 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x3201)*(x3202)))+(((sj7)*(x3204)))+(((cj7)*(npz)))+(((IkReal(-0.250000000000000))*(sj5))));
14765 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x3210)))+(((IkReal(-1.00000000000000))*(x3203)*(x3206)))+(((IkReal(-1.00000000000000))*(r10)*(x3209)))+(((IkReal(-1.00000000000000))*(r01)*(x3200))));
14766 evalcond[7]=((((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x3206)))+(((IkReal(-1.00000000000000))*(x3201)*(x3205)))+(((cj7)*(r10)*(x3200)))+(((IkReal(-1.00000000000000))*(r00)*(x3203)*(x3208)))+(((sj7)*(x3207)))+(((cj7)*(r01)*(x3209))));
14767 evalcond[8]=((((IkReal(-1.00000000000000))*(x3207)*(x3208)))+(((cj7)*(x3205)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x3201)))+(((r10)*(sj7)*(x3200)))+(((IkReal(-1.00000000000000))*(r00)*(x3201)*(x3203)))+(((r01)*(sj7)*(x3209))));
14768 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
14769 {
14770 {
14771 IkReal dummyeval[1];
14772 IkReal gconst52;
14773 gconst52=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
14774 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
14775 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14776 {
14777 {
14778 IkReal dummyeval[1];
14779 IkReal gconst53;
14780 gconst53=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
14781 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
14782 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
14783 {
14784 continue;
14785 
14786 } else
14787 {
14788 {
14789 IkReal j4array[1], cj4array[1], sj4array[1];
14790 bool j4valid[1]={false};
14791 _nj4 = 1;
14792 IkReal x3211=((cj3)*(cj5));
14793 IkReal x3212=((r02)*(sj7));
14794 IkReal x3213=((cj5)*(sj7));
14795 IkReal x3214=((cj3)*(sj5));
14796 IkReal x3215=((r11)*(sj3));
14797 IkReal x3216=((r10)*(sj3));
14798 IkReal x3217=((r12)*(sj3));
14799 IkReal x3218=((sj5)*(sj7));
14800 IkReal x3219=((cj7)*(cj8)*(sj5));
14801 IkReal x3220=((IkReal(1.00000000000000))*(cj7)*(sj8));
14802 IkReal x3221=((cj5)*(cj7)*(cj8));
14803 if( IKabs(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x3219)))+(((IkReal(-1.00000000000000))*(r22)*(x3218)))+(((x3216)*(x3221)))+(((x3211)*(x3212)))+(((x3213)*(x3217)))+(((cj7)*(cj8)*(r00)*(x3211)))+(((IkReal(-1.00000000000000))*(cj5)*(x3215)*(x3220)))+(((IkReal(-1.00000000000000))*(r01)*(x3211)*(x3220))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((x3212)*(x3214)))+(((IkReal(-1.00000000000000))*(r01)*(x3214)*(x3220)))+(((r22)*(x3213)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3220)))+(((IkReal(-1.00000000000000))*(sj5)*(x3215)*(x3220)))+(((cj7)*(cj8)*(r00)*(x3214)))+(((x3216)*(x3219)))+(((r20)*(x3221)))+(((x3217)*(x3218))))))) < IKFAST_ATAN2_MAGTHRESH )
14804  continue;
14805 j4array[0]=IKatan2(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r20)*(x3219)))+(((IkReal(-1.00000000000000))*(r22)*(x3218)))+(((x3216)*(x3221)))+(((x3211)*(x3212)))+(((x3213)*(x3217)))+(((cj7)*(cj8)*(r00)*(x3211)))+(((IkReal(-1.00000000000000))*(cj5)*(x3215)*(x3220)))+(((IkReal(-1.00000000000000))*(r01)*(x3211)*(x3220)))))), ((gconst53)*(((((x3212)*(x3214)))+(((IkReal(-1.00000000000000))*(r01)*(x3214)*(x3220)))+(((r22)*(x3213)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3220)))+(((IkReal(-1.00000000000000))*(sj5)*(x3215)*(x3220)))+(((cj7)*(cj8)*(r00)*(x3214)))+(((x3216)*(x3219)))+(((r20)*(x3221)))+(((x3217)*(x3218)))))));
14806 sj4array[0]=IKsin(j4array[0]);
14807 cj4array[0]=IKcos(j4array[0]);
14808 if( j4array[0] > IKPI )
14809 {
14810  j4array[0]-=IK2PI;
14811 }
14812 else if( j4array[0] < -IKPI )
14813 { j4array[0]+=IK2PI;
14814 }
14815 j4valid[0] = true;
14816 for(int ij4 = 0; ij4 < 1; ++ij4)
14817 {
14818 if( !j4valid[ij4] )
14819 {
14820  continue;
14821 }
14822 _ij4[0] = ij4; _ij4[1] = -1;
14823 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14824 {
14825 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14826 {
14827  j4valid[iij4]=false; _ij4[1] = iij4; break;
14828 }
14829 }
14830 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14831 {
14832 IkReal evalcond[4];
14833 IkReal x3222=IKcos(j4);
14834 IkReal x3223=IKsin(j4);
14835 IkReal x3224=((IkReal(1.00000000000000))*(cj7));
14836 IkReal x3225=((cj8)*(r20));
14837 IkReal x3226=((cj3)*(r02));
14838 IkReal x3227=((IkReal(1.00000000000000))*(sj7));
14839 IkReal x3228=((sj3)*(sj7));
14840 IkReal x3229=((r21)*(sj8));
14841 IkReal x3230=((cj8)*(r10));
14842 IkReal x3231=((sj5)*(x3222));
14843 IkReal x3232=((cj5)*(x3223));
14844 IkReal x3233=((r11)*(sj3)*(sj8));
14845 IkReal x3234=((cj3)*(cj8)*(r00));
14846 IkReal x3235=((cj5)*(x3222));
14847 IkReal x3236=((cj3)*(r01)*(sj8));
14848 IkReal x3237=((sj5)*(x3223));
14849 IkReal x3238=((x3232)+(x3231));
14850 evalcond[0]=((x3237)+(((IkReal(-1.00000000000000))*(x3224)*(x3225)))+(((cj7)*(x3229)))+(((IkReal(-1.00000000000000))*(x3235)))+(((IkReal(-1.00000000000000))*(r22)*(x3227))));
14851 evalcond[1]=((x3238)+(((IkReal(-1.00000000000000))*(x3225)*(x3227)))+(((sj7)*(x3229)))+(((cj7)*(r22))));
14852 evalcond[2]=((((r12)*(x3228)))+(((cj7)*(sj3)*(x3230)))+(x3238)+(((IkReal(-1.00000000000000))*(x3224)*(x3233)))+(((IkReal(-1.00000000000000))*(x3224)*(x3236)))+(((sj7)*(x3226)))+(((cj7)*(x3234))));
14853 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3224)))+(x3235)+(((IkReal(-1.00000000000000))*(x3224)*(x3226)))+(((IkReal(-1.00000000000000))*(x3237)))+(((IkReal(-1.00000000000000))*(x3227)*(x3233)))+(((IkReal(-1.00000000000000))*(x3227)*(x3236)))+(((x3228)*(x3230)))+(((sj7)*(x3234))));
14854 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
14855 {
14856 continue;
14857 }
14858 }
14859 
14860 {
14861 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14862 vinfos[0].jointtype = 1;
14863 vinfos[0].foffset = j3;
14864 vinfos[0].indices[0] = _ij3[0];
14865 vinfos[0].indices[1] = _ij3[1];
14866 vinfos[0].maxsolutions = _nj3;
14867 vinfos[1].jointtype = 1;
14868 vinfos[1].foffset = j4;
14869 vinfos[1].indices[0] = _ij4[0];
14870 vinfos[1].indices[1] = _ij4[1];
14871 vinfos[1].maxsolutions = _nj4;
14872 vinfos[2].jointtype = 1;
14873 vinfos[2].foffset = j5;
14874 vinfos[2].indices[0] = _ij5[0];
14875 vinfos[2].indices[1] = _ij5[1];
14876 vinfos[2].maxsolutions = _nj5;
14877 vinfos[3].jointtype = 1;
14878 vinfos[3].foffset = j6;
14879 vinfos[3].indices[0] = _ij6[0];
14880 vinfos[3].indices[1] = _ij6[1];
14881 vinfos[3].maxsolutions = _nj6;
14882 vinfos[4].jointtype = 1;
14883 vinfos[4].foffset = j7;
14884 vinfos[4].indices[0] = _ij7[0];
14885 vinfos[4].indices[1] = _ij7[1];
14886 vinfos[4].maxsolutions = _nj7;
14887 vinfos[5].jointtype = 1;
14888 vinfos[5].foffset = j8;
14889 vinfos[5].indices[0] = _ij8[0];
14890 vinfos[5].indices[1] = _ij8[1];
14891 vinfos[5].maxsolutions = _nj8;
14892 std::vector<int> vfree(0);
14893 solutions.AddSolution(vinfos,vfree);
14894 }
14895 }
14896 }
14897 
14898 }
14899 
14900 }
14901 
14902 } else
14903 {
14904 {
14905 IkReal j4array[1], cj4array[1], sj4array[1];
14906 bool j4valid[1]={false};
14907 _nj4 = 1;
14908 IkReal x3239=((r21)*(sj8));
14909 IkReal x3240=((sj5)*(sj7));
14910 IkReal x3241=((cj5)*(sj7));
14911 IkReal x3242=((cj5)*(cj7));
14912 IkReal x3243=((cj8)*(r20));
14913 IkReal x3244=((cj7)*(sj5));
14914 if( IKabs(((gconst52)*(((((r22)*(x3242)))+(((IkReal(-1.00000000000000))*(x3241)*(x3243)))+(((IkReal(-1.00000000000000))*(r22)*(x3240)))+(((x3239)*(x3244)))+(((x3239)*(x3241)))+(((IkReal(-1.00000000000000))*(x3243)*(x3244))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((r22)*(x3241)))+(((r22)*(x3244)))+(((IkReal(-1.00000000000000))*(x3239)*(x3242)))+(((IkReal(-1.00000000000000))*(x3240)*(x3243)))+(((x3239)*(x3240)))+(((x3242)*(x3243))))))) < IKFAST_ATAN2_MAGTHRESH )
14915  continue;
14916 j4array[0]=IKatan2(((gconst52)*(((((r22)*(x3242)))+(((IkReal(-1.00000000000000))*(x3241)*(x3243)))+(((IkReal(-1.00000000000000))*(r22)*(x3240)))+(((x3239)*(x3244)))+(((x3239)*(x3241)))+(((IkReal(-1.00000000000000))*(x3243)*(x3244)))))), ((gconst52)*(((((r22)*(x3241)))+(((r22)*(x3244)))+(((IkReal(-1.00000000000000))*(x3239)*(x3242)))+(((IkReal(-1.00000000000000))*(x3240)*(x3243)))+(((x3239)*(x3240)))+(((x3242)*(x3243)))))));
14917 sj4array[0]=IKsin(j4array[0]);
14918 cj4array[0]=IKcos(j4array[0]);
14919 if( j4array[0] > IKPI )
14920 {
14921  j4array[0]-=IK2PI;
14922 }
14923 else if( j4array[0] < -IKPI )
14924 { j4array[0]+=IK2PI;
14925 }
14926 j4valid[0] = true;
14927 for(int ij4 = 0; ij4 < 1; ++ij4)
14928 {
14929 if( !j4valid[ij4] )
14930 {
14931  continue;
14932 }
14933 _ij4[0] = ij4; _ij4[1] = -1;
14934 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14935 {
14936 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14937 {
14938  j4valid[iij4]=false; _ij4[1] = iij4; break;
14939 }
14940 }
14941 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14942 {
14943 IkReal evalcond[4];
14944 IkReal x3245=IKcos(j4);
14945 IkReal x3246=IKsin(j4);
14946 IkReal x3247=((IkReal(1.00000000000000))*(cj7));
14947 IkReal x3248=((cj8)*(r20));
14948 IkReal x3249=((cj3)*(r02));
14949 IkReal x3250=((IkReal(1.00000000000000))*(sj7));
14950 IkReal x3251=((sj3)*(sj7));
14951 IkReal x3252=((r21)*(sj8));
14952 IkReal x3253=((cj8)*(r10));
14953 IkReal x3254=((sj5)*(x3245));
14954 IkReal x3255=((cj5)*(x3246));
14955 IkReal x3256=((r11)*(sj3)*(sj8));
14956 IkReal x3257=((cj3)*(cj8)*(r00));
14957 IkReal x3258=((cj5)*(x3245));
14958 IkReal x3259=((cj3)*(r01)*(sj8));
14959 IkReal x3260=((sj5)*(x3246));
14960 IkReal x3261=((x3254)+(x3255));
14961 evalcond[0]=((x3260)+(((cj7)*(x3252)))+(((IkReal(-1.00000000000000))*(x3258)))+(((IkReal(-1.00000000000000))*(r22)*(x3250)))+(((IkReal(-1.00000000000000))*(x3247)*(x3248))));
14962 evalcond[1]=((x3261)+(((IkReal(-1.00000000000000))*(x3248)*(x3250)))+(((sj7)*(x3252)))+(((cj7)*(r22))));
14963 evalcond[2]=((((r12)*(x3251)))+(((sj7)*(x3249)))+(((IkReal(-1.00000000000000))*(x3247)*(x3256)))+(((IkReal(-1.00000000000000))*(x3247)*(x3259)))+(x3261)+(((cj7)*(sj3)*(x3253)))+(((cj7)*(x3257))));
14964 evalcond[3]=((((IkReal(-1.00000000000000))*(x3260)))+(x3258)+(((x3251)*(x3253)))+(((sj7)*(x3257)))+(((IkReal(-1.00000000000000))*(x3250)*(x3259)))+(((IkReal(-1.00000000000000))*(x3250)*(x3256)))+(((IkReal(-1.00000000000000))*(x3247)*(x3249)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3247))));
14965 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
14966 {
14967 continue;
14968 }
14969 }
14970 
14971 {
14972 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14973 vinfos[0].jointtype = 1;
14974 vinfos[0].foffset = j3;
14975 vinfos[0].indices[0] = _ij3[0];
14976 vinfos[0].indices[1] = _ij3[1];
14977 vinfos[0].maxsolutions = _nj3;
14978 vinfos[1].jointtype = 1;
14979 vinfos[1].foffset = j4;
14980 vinfos[1].indices[0] = _ij4[0];
14981 vinfos[1].indices[1] = _ij4[1];
14982 vinfos[1].maxsolutions = _nj4;
14983 vinfos[2].jointtype = 1;
14984 vinfos[2].foffset = j5;
14985 vinfos[2].indices[0] = _ij5[0];
14986 vinfos[2].indices[1] = _ij5[1];
14987 vinfos[2].maxsolutions = _nj5;
14988 vinfos[3].jointtype = 1;
14989 vinfos[3].foffset = j6;
14990 vinfos[3].indices[0] = _ij6[0];
14991 vinfos[3].indices[1] = _ij6[1];
14992 vinfos[3].maxsolutions = _nj6;
14993 vinfos[4].jointtype = 1;
14994 vinfos[4].foffset = j7;
14995 vinfos[4].indices[0] = _ij7[0];
14996 vinfos[4].indices[1] = _ij7[1];
14997 vinfos[4].maxsolutions = _nj7;
14998 vinfos[5].jointtype = 1;
14999 vinfos[5].foffset = j8;
15000 vinfos[5].indices[0] = _ij8[0];
15001 vinfos[5].indices[1] = _ij8[1];
15002 vinfos[5].maxsolutions = _nj8;
15003 std::vector<int> vfree(0);
15004 solutions.AddSolution(vinfos,vfree);
15005 }
15006 }
15007 }
15008 
15009 }
15010 
15011 }
15012 
15013 } else
15014 {
15015 IkReal x3262=((cj3)*(cj8));
15016 IkReal x3263=((IkReal(1.00000000000000))*(sj7));
15017 IkReal x3264=((cj8)*(npx));
15018 IkReal x3265=((cj8)*(sj3));
15019 IkReal x3266=((npy)*(sj8));
15020 IkReal x3267=((r02)*(sj3));
15021 IkReal x3268=((IkReal(1.00000000000000))*(r11));
15022 IkReal x3269=((cj3)*(r12));
15023 IkReal x3270=((IkReal(1.00000000000000))*(cj7));
15024 IkReal x3271=((sj3)*(sj8));
15025 IkReal x3272=((IkReal(1.00000000000000))*(cj3)*(sj8));
15026 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
15027 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
15028 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
15029 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(x3264)*(x3270)))+(((cj7)*(x3266)))+(((IkReal(-1.00000000000000))*(npz)*(x3263))));
15030 evalcond[4]=((IkReal(-1.00000000000000))+(((r01)*(x3265)))+(((r00)*(x3271)))+(((IkReal(-1.00000000000000))*(r10)*(x3272)))+(((IkReal(-1.00000000000000))*(x3262)*(x3268))));
15031 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x3266)))+(((IkReal(0.250000000000000))*(sj5)))+(((IkReal(-1.00000000000000))*(x3263)*(x3264)))+(((cj7)*(npz))));
15032 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x3272)))+(((IkReal(-1.00000000000000))*(x3265)*(x3268)))+(((IkReal(-1.00000000000000))*(r01)*(x3262)))+(((IkReal(-1.00000000000000))*(r10)*(x3271))));
15033 evalcond[7]=((((sj7)*(x3269)))+(((IkReal(-1.00000000000000))*(r00)*(x3265)*(x3270)))+(((cj7)*(r01)*(x3271)))+(((cj7)*(r10)*(x3262)))+(((IkReal(-1.00000000000000))*(x3263)*(x3267)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x3268))));
15034 evalcond[8]=((((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x3263)))+(((IkReal(-1.00000000000000))*(r00)*(x3263)*(x3265)))+(((IkReal(-1.00000000000000))*(x3269)*(x3270)))+(((cj7)*(x3267)))+(((r01)*(sj7)*(x3271)))+(((r10)*(sj7)*(x3262))));
15035 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
15036 {
15037 {
15038 IkReal dummyeval[1];
15039 IkReal gconst54;
15040 gconst54=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
15041 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
15042 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15043 {
15044 {
15045 IkReal dummyeval[1];
15046 IkReal gconst55;
15047 gconst55=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
15048 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
15049 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15050 {
15051 continue;
15052 
15053 } else
15054 {
15055 {
15056 IkReal j4array[1], cj4array[1], sj4array[1];
15057 bool j4valid[1]={false};
15058 _nj4 = 1;
15059 IkReal x3273=((cj3)*(cj5));
15060 IkReal x3274=((r02)*(sj7));
15061 IkReal x3275=((cj8)*(r00));
15062 IkReal x3276=((cj5)*(sj7));
15063 IkReal x3277=((cj5)*(sj3));
15064 IkReal x3278=((sj3)*(sj5));
15065 IkReal x3279=((IkReal(1.00000000000000))*(sj5));
15066 IkReal x3280=((cj3)*(cj7)*(sj5));
15067 IkReal x3281=((IkReal(1.00000000000000))*(cj7)*(sj8));
15068 IkReal x3282=((cj7)*(cj8)*(r10));
15069 IkReal x3283=((cj7)*(cj8)*(r20));
15070 if( IKabs(((gconst55)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(x3279)*(x3283)))+(((x3273)*(x3274)))+(((IkReal(-1.00000000000000))*(r01)*(x3273)*(x3281)))+(((cj7)*(x3273)*(x3275)))+(((r12)*(sj3)*(x3276)))+(((IkReal(-1.00000000000000))*(r11)*(x3277)*(x3281)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x3279)))+(((x3277)*(x3282))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((cj5)*(x3283)))+(((r12)*(sj7)*(x3278)))+(((x3275)*(x3280)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3281)))+(((r22)*(x3276)))+(((IkReal(-1.00000000000000))*(r11)*(x3278)*(x3281)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x3279)))+(((x3278)*(x3282)))+(((cj3)*(sj5)*(x3274))))))) < IKFAST_ATAN2_MAGTHRESH )
15071  continue;
15072 j4array[0]=IKatan2(((gconst55)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(x3279)*(x3283)))+(((x3273)*(x3274)))+(((IkReal(-1.00000000000000))*(r01)*(x3273)*(x3281)))+(((cj7)*(x3273)*(x3275)))+(((r12)*(sj3)*(x3276)))+(((IkReal(-1.00000000000000))*(r11)*(x3277)*(x3281)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x3279)))+(((x3277)*(x3282)))))), ((gconst55)*(((((cj5)*(x3283)))+(((r12)*(sj7)*(x3278)))+(((x3275)*(x3280)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3281)))+(((r22)*(x3276)))+(((IkReal(-1.00000000000000))*(r11)*(x3278)*(x3281)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x3279)))+(((x3278)*(x3282)))+(((cj3)*(sj5)*(x3274)))))));
15073 sj4array[0]=IKsin(j4array[0]);
15074 cj4array[0]=IKcos(j4array[0]);
15075 if( j4array[0] > IKPI )
15076 {
15077  j4array[0]-=IK2PI;
15078 }
15079 else if( j4array[0] < -IKPI )
15080 { j4array[0]+=IK2PI;
15081 }
15082 j4valid[0] = true;
15083 for(int ij4 = 0; ij4 < 1; ++ij4)
15084 {
15085 if( !j4valid[ij4] )
15086 {
15087  continue;
15088 }
15089 _ij4[0] = ij4; _ij4[1] = -1;
15090 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15091 {
15092 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15093 {
15094  j4valid[iij4]=false; _ij4[1] = iij4; break;
15095 }
15096 }
15097 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15098 {
15099 IkReal evalcond[4];
15100 IkReal x3284=IKcos(j4);
15101 IkReal x3285=IKsin(j4);
15102 IkReal x3286=((IkReal(1.00000000000000))*(cj7));
15103 IkReal x3287=((cj8)*(r20));
15104 IkReal x3288=((cj3)*(r02));
15105 IkReal x3289=((IkReal(1.00000000000000))*(sj7));
15106 IkReal x3290=((sj3)*(sj7));
15107 IkReal x3291=((r21)*(sj8));
15108 IkReal x3292=((IkReal(1.00000000000000))*(cj5));
15109 IkReal x3293=((cj8)*(r10));
15110 IkReal x3294=((sj5)*(x3285));
15111 IkReal x3295=((sj5)*(x3284));
15112 IkReal x3296=((r11)*(sj3)*(sj8));
15113 IkReal x3297=((cj3)*(cj8)*(r00));
15114 IkReal x3298=((cj3)*(r01)*(sj8));
15115 IkReal x3299=((x3284)*(x3292));
15116 evalcond[0]=((((IkReal(-1.00000000000000))*(x3299)))+(((IkReal(-1.00000000000000))*(r22)*(x3289)))+(x3294)+(((cj7)*(x3291)))+(((IkReal(-1.00000000000000))*(x3286)*(x3287))));
15117 evalcond[1]=((((sj7)*(x3291)))+(((IkReal(-1.00000000000000))*(x3287)*(x3289)))+(((IkReal(-1.00000000000000))*(x3295)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x3285)*(x3292))));
15118 evalcond[2]=((((sj7)*(x3288)))+(x3295)+(((cj5)*(x3285)))+(((cj7)*(x3297)))+(((cj7)*(sj3)*(x3293)))+(((r12)*(x3290)))+(((IkReal(-1.00000000000000))*(x3286)*(x3298)))+(((IkReal(-1.00000000000000))*(x3286)*(x3296))));
15119 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3286)))+(((sj7)*(x3297)))+(((IkReal(-1.00000000000000))*(x3299)))+(x3294)+(((x3290)*(x3293)))+(((IkReal(-1.00000000000000))*(x3289)*(x3296)))+(((IkReal(-1.00000000000000))*(x3289)*(x3298)))+(((IkReal(-1.00000000000000))*(x3286)*(x3288))));
15120 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
15121 {
15122 continue;
15123 }
15124 }
15125 
15126 {
15127 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15128 vinfos[0].jointtype = 1;
15129 vinfos[0].foffset = j3;
15130 vinfos[0].indices[0] = _ij3[0];
15131 vinfos[0].indices[1] = _ij3[1];
15132 vinfos[0].maxsolutions = _nj3;
15133 vinfos[1].jointtype = 1;
15134 vinfos[1].foffset = j4;
15135 vinfos[1].indices[0] = _ij4[0];
15136 vinfos[1].indices[1] = _ij4[1];
15137 vinfos[1].maxsolutions = _nj4;
15138 vinfos[2].jointtype = 1;
15139 vinfos[2].foffset = j5;
15140 vinfos[2].indices[0] = _ij5[0];
15141 vinfos[2].indices[1] = _ij5[1];
15142 vinfos[2].maxsolutions = _nj5;
15143 vinfos[3].jointtype = 1;
15144 vinfos[3].foffset = j6;
15145 vinfos[3].indices[0] = _ij6[0];
15146 vinfos[3].indices[1] = _ij6[1];
15147 vinfos[3].maxsolutions = _nj6;
15148 vinfos[4].jointtype = 1;
15149 vinfos[4].foffset = j7;
15150 vinfos[4].indices[0] = _ij7[0];
15151 vinfos[4].indices[1] = _ij7[1];
15152 vinfos[4].maxsolutions = _nj7;
15153 vinfos[5].jointtype = 1;
15154 vinfos[5].foffset = j8;
15155 vinfos[5].indices[0] = _ij8[0];
15156 vinfos[5].indices[1] = _ij8[1];
15157 vinfos[5].maxsolutions = _nj8;
15158 std::vector<int> vfree(0);
15159 solutions.AddSolution(vinfos,vfree);
15160 }
15161 }
15162 }
15163 
15164 }
15165 
15166 }
15167 
15168 } else
15169 {
15170 {
15171 IkReal j4array[1], cj4array[1], sj4array[1];
15172 bool j4valid[1]={false};
15173 _nj4 = 1;
15174 IkReal x3300=((cj7)*(sj5));
15175 IkReal x3301=((r21)*(sj8));
15176 IkReal x3302=((cj5)*(cj7));
15177 IkReal x3303=((cj8)*(r20));
15178 IkReal x3304=((IkReal(1.00000000000000))*(sj7));
15179 IkReal x3305=((sj5)*(sj7));
15180 if( IKabs(((gconst54)*(((((x3300)*(x3303)))+(((IkReal(-1.00000000000000))*(cj5)*(x3303)*(x3304)))+(((r22)*(x3305)))+(((r22)*(x3302)))+(((cj5)*(sj7)*(x3301)))+(((IkReal(-1.00000000000000))*(x3300)*(x3301))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((r22)*(x3300)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x3304)))+(((IkReal(-1.00000000000000))*(sj5)*(x3303)*(x3304)))+(((x3301)*(x3305)))+(((x3301)*(x3302)))+(((IkReal(-1.00000000000000))*(x3302)*(x3303))))))) < IKFAST_ATAN2_MAGTHRESH )
15181  continue;
15182 j4array[0]=IKatan2(((gconst54)*(((((x3300)*(x3303)))+(((IkReal(-1.00000000000000))*(cj5)*(x3303)*(x3304)))+(((r22)*(x3305)))+(((r22)*(x3302)))+(((cj5)*(sj7)*(x3301)))+(((IkReal(-1.00000000000000))*(x3300)*(x3301)))))), ((gconst54)*(((((r22)*(x3300)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x3304)))+(((IkReal(-1.00000000000000))*(sj5)*(x3303)*(x3304)))+(((x3301)*(x3305)))+(((x3301)*(x3302)))+(((IkReal(-1.00000000000000))*(x3302)*(x3303)))))));
15183 sj4array[0]=IKsin(j4array[0]);
15184 cj4array[0]=IKcos(j4array[0]);
15185 if( j4array[0] > IKPI )
15186 {
15187  j4array[0]-=IK2PI;
15188 }
15189 else if( j4array[0] < -IKPI )
15190 { j4array[0]+=IK2PI;
15191 }
15192 j4valid[0] = true;
15193 for(int ij4 = 0; ij4 < 1; ++ij4)
15194 {
15195 if( !j4valid[ij4] )
15196 {
15197  continue;
15198 }
15199 _ij4[0] = ij4; _ij4[1] = -1;
15200 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15201 {
15202 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15203 {
15204  j4valid[iij4]=false; _ij4[1] = iij4; break;
15205 }
15206 }
15207 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15208 {
15209 IkReal evalcond[4];
15210 IkReal x3306=IKcos(j4);
15211 IkReal x3307=IKsin(j4);
15212 IkReal x3308=((IkReal(1.00000000000000))*(cj7));
15213 IkReal x3309=((cj8)*(r20));
15214 IkReal x3310=((cj3)*(r02));
15215 IkReal x3311=((IkReal(1.00000000000000))*(sj7));
15216 IkReal x3312=((sj3)*(sj7));
15217 IkReal x3313=((r21)*(sj8));
15218 IkReal x3314=((IkReal(1.00000000000000))*(cj5));
15219 IkReal x3315=((cj8)*(r10));
15220 IkReal x3316=((sj5)*(x3307));
15221 IkReal x3317=((sj5)*(x3306));
15222 IkReal x3318=((r11)*(sj3)*(sj8));
15223 IkReal x3319=((cj3)*(cj8)*(r00));
15224 IkReal x3320=((cj3)*(r01)*(sj8));
15225 IkReal x3321=((x3306)*(x3314));
15226 evalcond[0]=((((IkReal(-1.00000000000000))*(x3321)))+(((cj7)*(x3313)))+(x3316)+(((IkReal(-1.00000000000000))*(r22)*(x3311)))+(((IkReal(-1.00000000000000))*(x3308)*(x3309))));
15227 evalcond[1]=((((sj7)*(x3313)))+(((IkReal(-1.00000000000000))*(x3309)*(x3311)))+(((IkReal(-1.00000000000000))*(x3317)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(x3307)*(x3314))));
15228 evalcond[2]=((((cj7)*(x3319)))+(x3317)+(((sj7)*(x3310)))+(((r12)*(x3312)))+(((cj7)*(sj3)*(x3315)))+(((IkReal(-1.00000000000000))*(x3308)*(x3318)))+(((IkReal(-1.00000000000000))*(x3308)*(x3320)))+(((cj5)*(x3307))));
15229 evalcond[3]=((((IkReal(-1.00000000000000))*(x3321)))+(((IkReal(-1.00000000000000))*(x3311)*(x3320)))+(x3316)+(((sj7)*(x3319)))+(((x3312)*(x3315)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3308)))+(((IkReal(-1.00000000000000))*(x3308)*(x3310)))+(((IkReal(-1.00000000000000))*(x3311)*(x3318))));
15230 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
15231 {
15232 continue;
15233 }
15234 }
15235 
15236 {
15237 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15238 vinfos[0].jointtype = 1;
15239 vinfos[0].foffset = j3;
15240 vinfos[0].indices[0] = _ij3[0];
15241 vinfos[0].indices[1] = _ij3[1];
15242 vinfos[0].maxsolutions = _nj3;
15243 vinfos[1].jointtype = 1;
15244 vinfos[1].foffset = j4;
15245 vinfos[1].indices[0] = _ij4[0];
15246 vinfos[1].indices[1] = _ij4[1];
15247 vinfos[1].maxsolutions = _nj4;
15248 vinfos[2].jointtype = 1;
15249 vinfos[2].foffset = j5;
15250 vinfos[2].indices[0] = _ij5[0];
15251 vinfos[2].indices[1] = _ij5[1];
15252 vinfos[2].maxsolutions = _nj5;
15253 vinfos[3].jointtype = 1;
15254 vinfos[3].foffset = j6;
15255 vinfos[3].indices[0] = _ij6[0];
15256 vinfos[3].indices[1] = _ij6[1];
15257 vinfos[3].maxsolutions = _nj6;
15258 vinfos[4].jointtype = 1;
15259 vinfos[4].foffset = j7;
15260 vinfos[4].indices[0] = _ij7[0];
15261 vinfos[4].indices[1] = _ij7[1];
15262 vinfos[4].maxsolutions = _nj7;
15263 vinfos[5].jointtype = 1;
15264 vinfos[5].foffset = j8;
15265 vinfos[5].indices[0] = _ij8[0];
15266 vinfos[5].indices[1] = _ij8[1];
15267 vinfos[5].maxsolutions = _nj8;
15268 std::vector<int> vfree(0);
15269 solutions.AddSolution(vinfos,vfree);
15270 }
15271 }
15272 }
15273 
15274 }
15275 
15276 }
15277 
15278 } else
15279 {
15280 if( 1 )
15281 {
15282 continue;
15283 
15284 } else
15285 {
15286 }
15287 }
15288 }
15289 }
15290 }
15291 }
15292 
15293 } else
15294 {
15295 {
15296 IkReal j4array[1], cj4array[1], sj4array[1];
15297 bool j4valid[1]={false};
15298 _nj4 = 1;
15299 IkReal x3322=((r21)*(sj8));
15300 IkReal x3323=((IkReal(1.00000000000000))*(r22));
15301 IkReal x3324=((cj5)*(sj7));
15302 IkReal x3325=((cj6)*(cj7));
15303 IkReal x3326=((sj5)*(sj7));
15304 IkReal x3327=((cj5)*(cj8)*(r20));
15305 IkReal x3328=((IkReal(1.00000000000000))*(x3325));
15306 IkReal x3329=((cj8)*(r20)*(sj5));
15307 if( IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x3322)*(x3324)))+(((x3325)*(x3329)))+(((cj6)*(r22)*(x3326)))+(((IkReal(-1.00000000000000))*(sj5)*(x3322)*(x3328)))+(((cj8)*(r20)*(x3324)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x3323))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x3322)*(x3326)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x3323)))+(((IkReal(-1.00000000000000))*(x3327)*(x3328)))+(((cj5)*(x3322)*(x3325)))+(((IkReal(-1.00000000000000))*(cj6)*(x3323)*(x3324)))+(((cj8)*(r20)*(x3326))))))) < IKFAST_ATAN2_MAGTHRESH )
15308  continue;
15309 j4array[0]=IKatan2(((gconst47)*(((((IkReal(-1.00000000000000))*(x3322)*(x3324)))+(((x3325)*(x3329)))+(((cj6)*(r22)*(x3326)))+(((IkReal(-1.00000000000000))*(sj5)*(x3322)*(x3328)))+(((cj8)*(r20)*(x3324)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x3323)))))), ((gconst47)*(((((IkReal(-1.00000000000000))*(x3322)*(x3326)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x3323)))+(((IkReal(-1.00000000000000))*(x3327)*(x3328)))+(((cj5)*(x3322)*(x3325)))+(((IkReal(-1.00000000000000))*(cj6)*(x3323)*(x3324)))+(((cj8)*(r20)*(x3326)))))));
15310 sj4array[0]=IKsin(j4array[0]);
15311 cj4array[0]=IKcos(j4array[0]);
15312 if( j4array[0] > IKPI )
15313 {
15314  j4array[0]-=IK2PI;
15315 }
15316 else if( j4array[0] < -IKPI )
15317 { j4array[0]+=IK2PI;
15318 }
15319 j4valid[0] = true;
15320 for(int ij4 = 0; ij4 < 1; ++ij4)
15321 {
15322 if( !j4valid[ij4] )
15323 {
15324  continue;
15325 }
15326 _ij4[0] = ij4; _ij4[1] = -1;
15327 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15328 {
15329 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15330 {
15331  j4valid[iij4]=false; _ij4[1] = iij4; break;
15332 }
15333 }
15334 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15335 {
15336 IkReal evalcond[6];
15337 IkReal x3330=IKsin(j4);
15338 IkReal x3331=IKcos(j4);
15339 IkReal x3332=((IkReal(1.00000000000000))*(cj8));
15340 IkReal x3333=((cj3)*(r01));
15341 IkReal x3334=((IkReal(1.00000000000000))*(sj8));
15342 IkReal x3335=((r11)*(sj3));
15343 IkReal x3336=((cj3)*(r00));
15344 IkReal x3337=((IkReal(1.00000000000000))*(sj6));
15345 IkReal x3338=((IkReal(1.00000000000000))*(cj7));
15346 IkReal x3339=((cj3)*(r02));
15347 IkReal x3340=((sj3)*(sj7));
15348 IkReal x3341=((cj7)*(cj8));
15349 IkReal x3342=((r21)*(sj8));
15350 IkReal x3343=((r10)*(sj3));
15351 IkReal x3344=((sj5)*(x3331));
15352 IkReal x3345=((cj5)*(x3331));
15353 IkReal x3346=((cj6)*(x3330));
15354 IkReal x3347=((cj5)*(x3330));
15355 IkReal x3348=((sj5)*(x3330));
15356 evalcond[0]=((((IkReal(-1.00000000000000))*(x3337)*(x3344)))+(((IkReal(-1.00000000000000))*(x3337)*(x3347)))+(((cj8)*(r21)))+(((r20)*(sj8))));
15357 evalcond[1]=((((IkReal(-1.00000000000000))*(x3345)))+(x3348)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3332)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(x3342))));
15358 evalcond[2]=((((cj5)*(x3346)))+(((IkReal(-1.00000000000000))*(r20)*(sj7)*(x3332)))+(((cj6)*(x3344)))+(((cj7)*(r22)))+(((sj7)*(x3342))));
15359 evalcond[3]=((((IkReal(-1.00000000000000))*(x3334)*(x3343)))+(((IkReal(-1.00000000000000))*(x3337)*(x3345)))+(((IkReal(-1.00000000000000))*(x3334)*(x3336)))+(((sj6)*(x3348)))+(((IkReal(-1.00000000000000))*(x3332)*(x3333)))+(((IkReal(-1.00000000000000))*(x3332)*(x3335))));
15360 evalcond[4]=((x3347)+(x3344)+(((sj7)*(x3339)))+(((x3341)*(x3343)))+(((IkReal(-1.00000000000000))*(cj7)*(x3333)*(x3334)))+(((x3336)*(x3341)))+(((IkReal(-1.00000000000000))*(cj7)*(x3334)*(x3335)))+(((r12)*(x3340))));
15361 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3338)))+(((IkReal(-1.00000000000000))*(x3338)*(x3339)))+(((IkReal(-1.00000000000000))*(sj7)*(x3333)*(x3334)))+(((IkReal(-1.00000000000000))*(sj7)*(x3334)*(x3335)))+(((IkReal(-1.00000000000000))*(sj5)*(x3346)))+(((cj8)*(sj7)*(x3336)))+(((cj6)*(x3345)))+(((cj8)*(r10)*(x3340))));
15362 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
15363 {
15364 continue;
15365 }
15366 }
15367 
15368 {
15369 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15370 vinfos[0].jointtype = 1;
15371 vinfos[0].foffset = j3;
15372 vinfos[0].indices[0] = _ij3[0];
15373 vinfos[0].indices[1] = _ij3[1];
15374 vinfos[0].maxsolutions = _nj3;
15375 vinfos[1].jointtype = 1;
15376 vinfos[1].foffset = j4;
15377 vinfos[1].indices[0] = _ij4[0];
15378 vinfos[1].indices[1] = _ij4[1];
15379 vinfos[1].maxsolutions = _nj4;
15380 vinfos[2].jointtype = 1;
15381 vinfos[2].foffset = j5;
15382 vinfos[2].indices[0] = _ij5[0];
15383 vinfos[2].indices[1] = _ij5[1];
15384 vinfos[2].maxsolutions = _nj5;
15385 vinfos[3].jointtype = 1;
15386 vinfos[3].foffset = j6;
15387 vinfos[3].indices[0] = _ij6[0];
15388 vinfos[3].indices[1] = _ij6[1];
15389 vinfos[3].maxsolutions = _nj6;
15390 vinfos[4].jointtype = 1;
15391 vinfos[4].foffset = j7;
15392 vinfos[4].indices[0] = _ij7[0];
15393 vinfos[4].indices[1] = _ij7[1];
15394 vinfos[4].maxsolutions = _nj7;
15395 vinfos[5].jointtype = 1;
15396 vinfos[5].foffset = j8;
15397 vinfos[5].indices[0] = _ij8[0];
15398 vinfos[5].indices[1] = _ij8[1];
15399 vinfos[5].maxsolutions = _nj8;
15400 std::vector<int> vfree(0);
15401 solutions.AddSolution(vinfos,vfree);
15402 }
15403 }
15404 }
15405 
15406 }
15407 
15408 }
15409 
15410 } else
15411 {
15412 {
15413 IkReal j4array[1], cj4array[1], sj4array[1];
15414 bool j4valid[1]={false};
15415 _nj4 = 1;
15416 IkReal x3349=((sj5)*(sj6));
15417 IkReal x3350=((r22)*(sj7));
15418 IkReal x3351=((r20)*(sj8));
15419 IkReal x3352=((cj8)*(r21));
15420 IkReal x3353=((cj5)*(sj6));
15421 IkReal x3354=((cj7)*(cj8)*(r20));
15422 IkReal x3355=((cj7)*(r21)*(sj8));
15423 if( IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(x3349)*(x3355)))+(((cj5)*(x3351)))+(((cj5)*(x3352)))+(((x3349)*(x3350)))+(((x3349)*(x3354))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(x3350)*(x3353)))+(((IkReal(-1.00000000000000))*(x3353)*(x3354)))+(((x3353)*(x3355)))+(((sj5)*(x3351)))+(((sj5)*(x3352))))))) < IKFAST_ATAN2_MAGTHRESH )
15424  continue;
15425 j4array[0]=IKatan2(((gconst46)*(((((IkReal(-1.00000000000000))*(x3349)*(x3355)))+(((cj5)*(x3351)))+(((cj5)*(x3352)))+(((x3349)*(x3350)))+(((x3349)*(x3354)))))), ((gconst46)*(((((IkReal(-1.00000000000000))*(x3350)*(x3353)))+(((IkReal(-1.00000000000000))*(x3353)*(x3354)))+(((x3353)*(x3355)))+(((sj5)*(x3351)))+(((sj5)*(x3352)))))));
15426 sj4array[0]=IKsin(j4array[0]);
15427 cj4array[0]=IKcos(j4array[0]);
15428 if( j4array[0] > IKPI )
15429 {
15430  j4array[0]-=IK2PI;
15431 }
15432 else if( j4array[0] < -IKPI )
15433 { j4array[0]+=IK2PI;
15434 }
15435 j4valid[0] = true;
15436 for(int ij4 = 0; ij4 < 1; ++ij4)
15437 {
15438 if( !j4valid[ij4] )
15439 {
15440  continue;
15441 }
15442 _ij4[0] = ij4; _ij4[1] = -1;
15443 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15444 {
15445 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15446 {
15447  j4valid[iij4]=false; _ij4[1] = iij4; break;
15448 }
15449 }
15450 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15451 {
15452 IkReal evalcond[6];
15453 IkReal x3356=IKsin(j4);
15454 IkReal x3357=IKcos(j4);
15455 IkReal x3358=((IkReal(1.00000000000000))*(cj8));
15456 IkReal x3359=((cj3)*(r01));
15457 IkReal x3360=((IkReal(1.00000000000000))*(sj8));
15458 IkReal x3361=((r11)*(sj3));
15459 IkReal x3362=((cj3)*(r00));
15460 IkReal x3363=((IkReal(1.00000000000000))*(sj6));
15461 IkReal x3364=((IkReal(1.00000000000000))*(cj7));
15462 IkReal x3365=((cj3)*(r02));
15463 IkReal x3366=((sj3)*(sj7));
15464 IkReal x3367=((cj7)*(cj8));
15465 IkReal x3368=((r21)*(sj8));
15466 IkReal x3369=((r10)*(sj3));
15467 IkReal x3370=((sj5)*(x3357));
15468 IkReal x3371=((cj5)*(x3357));
15469 IkReal x3372=((cj6)*(x3356));
15470 IkReal x3373=((cj5)*(x3356));
15471 IkReal x3374=((sj5)*(x3356));
15472 evalcond[0]=((((IkReal(-1.00000000000000))*(x3363)*(x3370)))+(((IkReal(-1.00000000000000))*(x3363)*(x3373)))+(((cj8)*(r21)))+(((r20)*(sj8))));
15473 evalcond[1]=((((IkReal(-1.00000000000000))*(x3371)))+(((cj7)*(x3368)))+(x3374)+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3358)))+(((IkReal(-1.00000000000000))*(r22)*(sj7))));
15474 evalcond[2]=((((cj5)*(x3372)))+(((IkReal(-1.00000000000000))*(r20)*(sj7)*(x3358)))+(((sj7)*(x3368)))+(((cj6)*(x3370)))+(((cj7)*(r22))));
15475 evalcond[3]=((((IkReal(-1.00000000000000))*(x3360)*(x3369)))+(((IkReal(-1.00000000000000))*(x3360)*(x3362)))+(((IkReal(-1.00000000000000))*(x3363)*(x3371)))+(((IkReal(-1.00000000000000))*(x3358)*(x3359)))+(((sj6)*(x3374)))+(((IkReal(-1.00000000000000))*(x3358)*(x3361))));
15476 evalcond[4]=((((x3362)*(x3367)))+(((x3367)*(x3369)))+(x3373)+(x3370)+(((sj7)*(x3365)))+(((IkReal(-1.00000000000000))*(cj7)*(x3360)*(x3361)))+(((IkReal(-1.00000000000000))*(cj7)*(x3359)*(x3360)))+(((r12)*(x3366))));
15477 evalcond[5]=((((IkReal(-1.00000000000000))*(sj7)*(x3359)*(x3360)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3364)))+(((cj8)*(r10)*(x3366)))+(((IkReal(-1.00000000000000))*(x3364)*(x3365)))+(((cj8)*(sj7)*(x3362)))+(((IkReal(-1.00000000000000))*(sj5)*(x3372)))+(((IkReal(-1.00000000000000))*(sj7)*(x3360)*(x3361)))+(((cj6)*(x3371))));
15478 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
15479 {
15480 continue;
15481 }
15482 }
15483 
15484 {
15485 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15486 vinfos[0].jointtype = 1;
15487 vinfos[0].foffset = j3;
15488 vinfos[0].indices[0] = _ij3[0];
15489 vinfos[0].indices[1] = _ij3[1];
15490 vinfos[0].maxsolutions = _nj3;
15491 vinfos[1].jointtype = 1;
15492 vinfos[1].foffset = j4;
15493 vinfos[1].indices[0] = _ij4[0];
15494 vinfos[1].indices[1] = _ij4[1];
15495 vinfos[1].maxsolutions = _nj4;
15496 vinfos[2].jointtype = 1;
15497 vinfos[2].foffset = j5;
15498 vinfos[2].indices[0] = _ij5[0];
15499 vinfos[2].indices[1] = _ij5[1];
15500 vinfos[2].maxsolutions = _nj5;
15501 vinfos[3].jointtype = 1;
15502 vinfos[3].foffset = j6;
15503 vinfos[3].indices[0] = _ij6[0];
15504 vinfos[3].indices[1] = _ij6[1];
15505 vinfos[3].maxsolutions = _nj6;
15506 vinfos[4].jointtype = 1;
15507 vinfos[4].foffset = j7;
15508 vinfos[4].indices[0] = _ij7[0];
15509 vinfos[4].indices[1] = _ij7[1];
15510 vinfos[4].maxsolutions = _nj7;
15511 vinfos[5].jointtype = 1;
15512 vinfos[5].foffset = j8;
15513 vinfos[5].indices[0] = _ij8[0];
15514 vinfos[5].indices[1] = _ij8[1];
15515 vinfos[5].maxsolutions = _nj8;
15516 std::vector<int> vfree(0);
15517 solutions.AddSolution(vinfos,vfree);
15518 }
15519 }
15520 }
15521 
15522 }
15523 
15524 }
15525 }
15526 }
15527 
15528 }
15529 
15530 }
15531 
15532 } else
15533 {
15534 {
15535 IkReal j5array[1], cj5array[1], sj5array[1];
15536 bool j5valid[1]={false};
15537 _nj5 = 1;
15538 IkReal x3375=((IkReal(4.00000000000000))*(npx));
15539 IkReal x3376=((IkReal(4.00000000000000))*(npy));
15540 if( IKabs(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(sj8)*(x3375)))+(((IkReal(-1.00000000000000))*(cj8)*(x3376))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((cj7)*(cj8)*(x3375)))+(((IkReal(-0.360000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x3376))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(sj8)*(x3375)))+(((IkReal(-1.00000000000000))*(cj8)*(x3376)))))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((cj7)*(cj8)*(x3375)))+(((IkReal(-0.360000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x3376)))))-1) <= IKFAST_SINCOS_THRESH )
15541  continue;
15542 j5array[0]=IKatan2(((((IKabs(sj6) != 0)?((IkReal)1/(sj6)):(IkReal)1.0e30))*(((((IkReal(0.380000000000000))*(cj6)))+(((IkReal(0.120000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(sj8)*(x3375)))+(((IkReal(-1.00000000000000))*(cj8)*(x3376)))))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj7)))+(((cj7)*(cj8)*(x3375)))+(((IkReal(-0.360000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(cj7)*(sj8)*(x3376)))));
15543 sj5array[0]=IKsin(j5array[0]);
15544 cj5array[0]=IKcos(j5array[0]);
15545 if( j5array[0] > IKPI )
15546 {
15547  j5array[0]-=IK2PI;
15548 }
15549 else if( j5array[0] < -IKPI )
15550 { j5array[0]+=IK2PI;
15551 }
15552 j5valid[0] = true;
15553 for(int ij5 = 0; ij5 < 1; ++ij5)
15554 {
15555 if( !j5valid[ij5] )
15556 {
15557  continue;
15558 }
15559 _ij5[0] = ij5; _ij5[1] = -1;
15560 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
15561 {
15562 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
15563 {
15564  j5valid[iij5]=false; _ij5[1] = iij5; break;
15565 }
15566 }
15567 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
15568 {
15569 IkReal evalcond[3];
15570 IkReal x3377=IKsin(j5);
15571 IkReal x3378=((IkReal(1.00000000000000))*(sj7));
15572 IkReal x3379=((npy)*(sj8));
15573 IkReal x3380=((cj8)*(npx));
15574 IkReal x3381=((IkReal(0.250000000000000))*(x3377));
15575 evalcond[0]=((((IkReal(-0.0300000000000000))*(sj6)))+(((IkReal(-0.0950000000000000))*(cj6)))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((sj6)*(x3381))));
15576 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x3378)))+(((IkReal(-1.00000000000000))*(cj7)*(x3380)))+(((IkReal(0.250000000000000))*(IKcos(j5))))+(((cj7)*(x3379))));
15577 evalcond[2]=((((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x3378)*(x3380)))+(((IkReal(0.0300000000000000))*(cj6)))+(((IkReal(-0.0950000000000000))*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(x3381)))+(((cj7)*(npz)))+(((sj7)*(x3379))));
15578 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 )
15579 {
15580 continue;
15581 }
15582 }
15583 
15584 {
15585 IkReal dummyeval[1];
15586 IkReal gconst46;
15587 gconst46=IKsign(((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5))))));
15588 dummyeval[0]=((((sj6)*((cj5)*(cj5))))+(((sj6)*((sj5)*(sj5)))));
15589 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15590 {
15591 {
15592 IkReal dummyeval[1];
15593 IkReal gconst47;
15594 gconst47=IKsign(((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5))))));
15595 dummyeval[0]=((((cj6)*((cj5)*(cj5))))+(((cj6)*((sj5)*(sj5)))));
15596 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15597 {
15598 {
15599 IkReal evalcond[9];
15600 IkReal x3382=((IkReal(1.00000000000000))*(sj7));
15601 IkReal x3383=((IkReal(1.00000000000000))*(cj3));
15602 IkReal x3384=((cj7)*(r02));
15603 IkReal x3385=((cj8)*(r00));
15604 IkReal x3386=((cj3)*(sj7));
15605 IkReal x3387=((cj8)*(npx));
15606 IkReal x3388=((r01)*(sj3));
15607 IkReal x3389=((cj7)*(sj8));
15608 IkReal x3390=((r11)*(sj8));
15609 IkReal x3391=((IkReal(1.00000000000000))*(cj7));
15610 IkReal x3392=((sj7)*(sj8));
15611 IkReal x3393=((cj8)*(r10));
15612 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j6)), IkReal(6.28318530717959))));
15613 evalcond[1]=((IkReal(-0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(0.250000000000000))*(sj5))));
15614 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(x3387)*(x3391)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x3382)))+(((npy)*(x3389))));
15615 evalcond[3]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x3383)))+(((r00)*(sj3)*(sj8)))+(((cj8)*(x3388)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x3383))));
15616 evalcond[4]=((((r21)*(x3392)))+(((cj7)*(r22)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x3382))));
15617 evalcond[5]=((IkReal(-0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(-1.00000000000000))*(x3382)*(x3387)))+(((cj7)*(npz)))+(((npy)*(x3392))));
15618 evalcond[6]=((((cj3)*(cj7)*(x3393)))+(((x3388)*(x3389)))+(((r12)*(x3386)))+(((IkReal(-1.00000000000000))*(sj3)*(x3385)*(x3391)))+(((IkReal(-1.00000000000000))*(r11)*(x3383)*(x3389)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x3382))));
15619 evalcond[7]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x3382)*(x3390)))+(((x3386)*(x3393)))+(((x3388)*(x3392)))+(((IkReal(-1.00000000000000))*(sj3)*(x3382)*(x3385)))+(((sj3)*(x3384)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x3383))));
15620 evalcond[8]=((((IkReal(-1.00000000000000))*(x3383)*(x3384)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3391)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x3382)))+(((sj3)*(sj7)*(x3393)))+(((IkReal(-1.00000000000000))*(sj3)*(x3382)*(x3390)))+(((x3385)*(x3386))));
15621 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
15622 {
15623 {
15624 IkReal dummyeval[1];
15625 IkReal gconst48;
15626 gconst48=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
15627 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
15628 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15629 {
15630 {
15631 IkReal dummyeval[1];
15632 IkReal gconst49;
15633 gconst49=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
15634 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
15635 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15636 {
15637 continue;
15638 
15639 } else
15640 {
15641 {
15642 IkReal j4array[1], cj4array[1], sj4array[1];
15643 bool j4valid[1]={false};
15644 _nj4 = 1;
15645 IkReal x3394=((cj8)*(sj5));
15646 IkReal x3395=((cj3)*(r01));
15647 IkReal x3396=((IkReal(1.00000000000000))*(cj5));
15648 IkReal x3397=((r11)*(sj3));
15649 IkReal x3398=((sj5)*(sj8));
15650 IkReal x3399=((r10)*(sj3));
15651 IkReal x3400=((cj3)*(r00)*(sj8));
15652 if( IKabs(((gconst49)*(((((cj3)*(r00)*(x3398)))+(((x3394)*(x3397)))+(((x3394)*(x3395)))+(((cj5)*(r20)*(sj8)))+(((x3398)*(x3399)))+(((cj5)*(cj8)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((r20)*(x3398)))+(((IkReal(-1.00000000000000))*(cj8)*(x3396)*(x3397)))+(((IkReal(-1.00000000000000))*(x3396)*(x3400)))+(((r21)*(x3394)))+(((IkReal(-1.00000000000000))*(sj8)*(x3396)*(x3399)))+(((IkReal(-1.00000000000000))*(cj8)*(x3395)*(x3396))))))) < IKFAST_ATAN2_MAGTHRESH )
15653  continue;
15654 j4array[0]=IKatan2(((gconst49)*(((((cj3)*(r00)*(x3398)))+(((x3394)*(x3397)))+(((x3394)*(x3395)))+(((cj5)*(r20)*(sj8)))+(((x3398)*(x3399)))+(((cj5)*(cj8)*(r21)))))), ((gconst49)*(((((r20)*(x3398)))+(((IkReal(-1.00000000000000))*(cj8)*(x3396)*(x3397)))+(((IkReal(-1.00000000000000))*(x3396)*(x3400)))+(((r21)*(x3394)))+(((IkReal(-1.00000000000000))*(sj8)*(x3396)*(x3399)))+(((IkReal(-1.00000000000000))*(cj8)*(x3395)*(x3396)))))));
15655 sj4array[0]=IKsin(j4array[0]);
15656 cj4array[0]=IKcos(j4array[0]);
15657 if( j4array[0] > IKPI )
15658 {
15659  j4array[0]-=IK2PI;
15660 }
15661 else if( j4array[0] < -IKPI )
15662 { j4array[0]+=IK2PI;
15663 }
15664 j4valid[0] = true;
15665 for(int ij4 = 0; ij4 < 1; ++ij4)
15666 {
15667 if( !j4valid[ij4] )
15668 {
15669  continue;
15670 }
15671 _ij4[0] = ij4; _ij4[1] = -1;
15672 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15673 {
15674 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15675 {
15676  j4valid[iij4]=false; _ij4[1] = iij4; break;
15677 }
15678 }
15679 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15680 {
15681 IkReal evalcond[4];
15682 IkReal x3401=IKsin(j4);
15683 IkReal x3402=IKcos(j4);
15684 IkReal x3403=((IkReal(1.00000000000000))*(cj8));
15685 IkReal x3404=((cj3)*(r01));
15686 IkReal x3405=((cj3)*(r00));
15687 IkReal x3406=((cj7)*(cj8));
15688 IkReal x3407=((IkReal(1.00000000000000))*(cj5));
15689 IkReal x3408=((IkReal(1.00000000000000))*(sj8));
15690 IkReal x3409=((r11)*(sj3));
15691 IkReal x3410=((r10)*(sj3));
15692 IkReal x3411=((sj5)*(x3401));
15693 IkReal x3412=((sj5)*(x3402));
15694 IkReal x3413=((x3402)*(x3407));
15695 evalcond[0]=((((IkReal(-1.00000000000000))*(x3412)))+(((IkReal(-1.00000000000000))*(x3401)*(x3407)))+(((cj8)*(r21)))+(((r20)*(sj8))));
15696 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3403)))+(x3411)+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8)))+(((IkReal(-1.00000000000000))*(x3413))));
15697 evalcond[2]=((((IkReal(-1.00000000000000))*(x3405)*(x3408)))+(((IkReal(-1.00000000000000))*(x3408)*(x3410)))+(x3411)+(((IkReal(-1.00000000000000))*(x3403)*(x3409)))+(((IkReal(-1.00000000000000))*(x3403)*(x3404)))+(((IkReal(-1.00000000000000))*(x3413))));
15698 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x3406)*(x3410)))+(x3412)+(((IkReal(-1.00000000000000))*(cj7)*(x3408)*(x3409)))+(((x3405)*(x3406)))+(((cj3)*(r02)*(sj7)))+(((cj5)*(x3401)))+(((IkReal(-1.00000000000000))*(cj7)*(x3404)*(x3408))));
15699 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
15700 {
15701 continue;
15702 }
15703 }
15704 
15705 {
15706 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15707 vinfos[0].jointtype = 1;
15708 vinfos[0].foffset = j3;
15709 vinfos[0].indices[0] = _ij3[0];
15710 vinfos[0].indices[1] = _ij3[1];
15711 vinfos[0].maxsolutions = _nj3;
15712 vinfos[1].jointtype = 1;
15713 vinfos[1].foffset = j4;
15714 vinfos[1].indices[0] = _ij4[0];
15715 vinfos[1].indices[1] = _ij4[1];
15716 vinfos[1].maxsolutions = _nj4;
15717 vinfos[2].jointtype = 1;
15718 vinfos[2].foffset = j5;
15719 vinfos[2].indices[0] = _ij5[0];
15720 vinfos[2].indices[1] = _ij5[1];
15721 vinfos[2].maxsolutions = _nj5;
15722 vinfos[3].jointtype = 1;
15723 vinfos[3].foffset = j6;
15724 vinfos[3].indices[0] = _ij6[0];
15725 vinfos[3].indices[1] = _ij6[1];
15726 vinfos[3].maxsolutions = _nj6;
15727 vinfos[4].jointtype = 1;
15728 vinfos[4].foffset = j7;
15729 vinfos[4].indices[0] = _ij7[0];
15730 vinfos[4].indices[1] = _ij7[1];
15731 vinfos[4].maxsolutions = _nj7;
15732 vinfos[5].jointtype = 1;
15733 vinfos[5].foffset = j8;
15734 vinfos[5].indices[0] = _ij8[0];
15735 vinfos[5].indices[1] = _ij8[1];
15736 vinfos[5].maxsolutions = _nj8;
15737 std::vector<int> vfree(0);
15738 solutions.AddSolution(vinfos,vfree);
15739 }
15740 }
15741 }
15742 
15743 }
15744 
15745 }
15746 
15747 } else
15748 {
15749 {
15750 IkReal j4array[1], cj4array[1], sj4array[1];
15751 bool j4valid[1]={false};
15752 _nj4 = 1;
15753 IkReal x3414=((sj5)*(sj8));
15754 IkReal x3415=((IkReal(1.00000000000000))*(cj7));
15755 IkReal x3416=((r22)*(sj7));
15756 IkReal x3417=((cj8)*(sj5));
15757 IkReal x3418=((cj5)*(cj8));
15758 IkReal x3419=((cj5)*(sj8));
15759 if( IKabs(((gconst48)*(((((IkReal(-1.00000000000000))*(r21)*(x3414)*(x3415)))+(((r21)*(x3418)))+(((sj5)*(x3416)))+(((r20)*(x3419)))+(((cj7)*(r20)*(x3417))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((IkReal(-1.00000000000000))*(r20)*(x3415)*(x3418)))+(((r21)*(x3417)))+(((IkReal(-1.00000000000000))*(cj5)*(x3416)))+(((r20)*(x3414)))+(((cj7)*(r21)*(x3419))))))) < IKFAST_ATAN2_MAGTHRESH )
15760  continue;
15761 j4array[0]=IKatan2(((gconst48)*(((((IkReal(-1.00000000000000))*(r21)*(x3414)*(x3415)))+(((r21)*(x3418)))+(((sj5)*(x3416)))+(((r20)*(x3419)))+(((cj7)*(r20)*(x3417)))))), ((gconst48)*(((((IkReal(-1.00000000000000))*(r20)*(x3415)*(x3418)))+(((r21)*(x3417)))+(((IkReal(-1.00000000000000))*(cj5)*(x3416)))+(((r20)*(x3414)))+(((cj7)*(r21)*(x3419)))))));
15762 sj4array[0]=IKsin(j4array[0]);
15763 cj4array[0]=IKcos(j4array[0]);
15764 if( j4array[0] > IKPI )
15765 {
15766  j4array[0]-=IK2PI;
15767 }
15768 else if( j4array[0] < -IKPI )
15769 { j4array[0]+=IK2PI;
15770 }
15771 j4valid[0] = true;
15772 for(int ij4 = 0; ij4 < 1; ++ij4)
15773 {
15774 if( !j4valid[ij4] )
15775 {
15776  continue;
15777 }
15778 _ij4[0] = ij4; _ij4[1] = -1;
15779 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15780 {
15781 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15782 {
15783  j4valid[iij4]=false; _ij4[1] = iij4; break;
15784 }
15785 }
15786 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15787 {
15788 IkReal evalcond[4];
15789 IkReal x3420=IKsin(j4);
15790 IkReal x3421=IKcos(j4);
15791 IkReal x3422=((IkReal(1.00000000000000))*(cj8));
15792 IkReal x3423=((cj3)*(r01));
15793 IkReal x3424=((cj3)*(r00));
15794 IkReal x3425=((cj7)*(cj8));
15795 IkReal x3426=((IkReal(1.00000000000000))*(cj5));
15796 IkReal x3427=((IkReal(1.00000000000000))*(sj8));
15797 IkReal x3428=((r11)*(sj3));
15798 IkReal x3429=((r10)*(sj3));
15799 IkReal x3430=((sj5)*(x3420));
15800 IkReal x3431=((sj5)*(x3421));
15801 IkReal x3432=((x3421)*(x3426));
15802 evalcond[0]=((((IkReal(-1.00000000000000))*(x3420)*(x3426)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x3431)))+(((r20)*(sj8))));
15803 evalcond[1]=((x3430)+(((IkReal(-1.00000000000000))*(x3432)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3422)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(r21)*(sj8))));
15804 evalcond[2]=((((IkReal(-1.00000000000000))*(x3427)*(x3429)))+(((IkReal(-1.00000000000000))*(x3424)*(x3427)))+(x3430)+(((IkReal(-1.00000000000000))*(x3432)))+(((IkReal(-1.00000000000000))*(x3422)*(x3423)))+(((IkReal(-1.00000000000000))*(x3422)*(x3428))));
15805 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((x3424)*(x3425)))+(((x3425)*(x3429)))+(((IkReal(-1.00000000000000))*(cj7)*(x3427)*(x3428)))+(x3431)+(((cj5)*(x3420)))+(((IkReal(-1.00000000000000))*(cj7)*(x3423)*(x3427)))+(((cj3)*(r02)*(sj7))));
15806 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
15807 {
15808 continue;
15809 }
15810 }
15811 
15812 {
15813 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15814 vinfos[0].jointtype = 1;
15815 vinfos[0].foffset = j3;
15816 vinfos[0].indices[0] = _ij3[0];
15817 vinfos[0].indices[1] = _ij3[1];
15818 vinfos[0].maxsolutions = _nj3;
15819 vinfos[1].jointtype = 1;
15820 vinfos[1].foffset = j4;
15821 vinfos[1].indices[0] = _ij4[0];
15822 vinfos[1].indices[1] = _ij4[1];
15823 vinfos[1].maxsolutions = _nj4;
15824 vinfos[2].jointtype = 1;
15825 vinfos[2].foffset = j5;
15826 vinfos[2].indices[0] = _ij5[0];
15827 vinfos[2].indices[1] = _ij5[1];
15828 vinfos[2].maxsolutions = _nj5;
15829 vinfos[3].jointtype = 1;
15830 vinfos[3].foffset = j6;
15831 vinfos[3].indices[0] = _ij6[0];
15832 vinfos[3].indices[1] = _ij6[1];
15833 vinfos[3].maxsolutions = _nj6;
15834 vinfos[4].jointtype = 1;
15835 vinfos[4].foffset = j7;
15836 vinfos[4].indices[0] = _ij7[0];
15837 vinfos[4].indices[1] = _ij7[1];
15838 vinfos[4].maxsolutions = _nj7;
15839 vinfos[5].jointtype = 1;
15840 vinfos[5].foffset = j8;
15841 vinfos[5].indices[0] = _ij8[0];
15842 vinfos[5].indices[1] = _ij8[1];
15843 vinfos[5].maxsolutions = _nj8;
15844 std::vector<int> vfree(0);
15845 solutions.AddSolution(vinfos,vfree);
15846 }
15847 }
15848 }
15849 
15850 }
15851 
15852 }
15853 
15854 } else
15855 {
15856 IkReal x3433=((IkReal(1.00000000000000))*(sj7));
15857 IkReal x3434=((IkReal(1.00000000000000))*(cj3));
15858 IkReal x3435=((cj7)*(r02));
15859 IkReal x3436=((cj8)*(r00));
15860 IkReal x3437=((cj3)*(sj7));
15861 IkReal x3438=((cj8)*(npx));
15862 IkReal x3439=((r01)*(sj3));
15863 IkReal x3440=((cj7)*(sj8));
15864 IkReal x3441=((r11)*(sj8));
15865 IkReal x3442=((IkReal(1.00000000000000))*(cj7));
15866 IkReal x3443=((sj7)*(sj8));
15867 IkReal x3444=((cj8)*(r10));
15868 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j6)), IkReal(6.28318530717959))));
15869 evalcond[1]=((IkReal(0.0300000000000000))+(((npx)*(sj8)))+(((cj8)*(npy)))+(((IkReal(-0.250000000000000))*(sj5))));
15870 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(x3438)*(x3442)))+(((npy)*(x3440)))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(0.250000000000000))*(cj5)))+(((IkReal(-1.00000000000000))*(npz)*(x3433))));
15871 evalcond[3]=((((IkReal(-1.00000000000000))*(cj8)*(r11)*(x3434)))+(((IkReal(-1.00000000000000))*(r10)*(sj8)*(x3434)))+(((r00)*(sj3)*(sj8)))+(((cj8)*(x3439))));
15872 evalcond[4]=((((r21)*(x3443)))+(((IkReal(-1.00000000000000))*(cj8)*(r20)*(x3433)))+(((cj7)*(r22))));
15873 evalcond[5]=((IkReal(0.0950000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((npy)*(x3443)))+(((IkReal(-1.00000000000000))*(x3433)*(x3438)))+(((cj7)*(npz))));
15874 evalcond[6]=((((cj3)*(cj7)*(x3444)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x3433)))+(((IkReal(-1.00000000000000))*(r11)*(x3434)*(x3440)))+(((IkReal(-1.00000000000000))*(sj3)*(x3436)*(x3442)))+(((r12)*(x3437)))+(((x3439)*(x3440))));
15875 evalcond[7]=((IkReal(-1.00000000000000))+(((sj3)*(x3435)))+(((IkReal(-1.00000000000000))*(cj3)*(x3433)*(x3441)))+(((x3437)*(x3444)))+(((IkReal(-1.00000000000000))*(cj7)*(r12)*(x3434)))+(((IkReal(-1.00000000000000))*(sj3)*(x3433)*(x3436)))+(((x3439)*(x3443))));
15876 evalcond[8]=((((IkReal(-1.00000000000000))*(sj3)*(x3433)*(x3441)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3442)))+(((IkReal(-1.00000000000000))*(x3434)*(x3435)))+(((sj3)*(sj7)*(x3444)))+(((x3436)*(x3437)))+(((IkReal(-1.00000000000000))*(cj3)*(r01)*(sj8)*(x3433))));
15877 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
15878 {
15879 {
15880 IkReal dummyeval[1];
15881 IkReal gconst50;
15882 gconst50=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
15883 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
15884 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15885 {
15886 {
15887 IkReal dummyeval[1];
15888 IkReal gconst51;
15889 gconst51=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
15890 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
15891 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
15892 {
15893 continue;
15894 
15895 } else
15896 {
15897 {
15898 IkReal j4array[1], cj4array[1], sj4array[1];
15899 bool j4valid[1]={false};
15900 _nj4 = 1;
15901 IkReal x3445=((IkReal(1.00000000000000))*(sj5));
15902 IkReal x3446=((r20)*(sj8));
15903 IkReal x3447=((cj5)*(cj8));
15904 IkReal x3448=((r11)*(sj3));
15905 IkReal x3449=((cj3)*(r01));
15906 IkReal x3450=((cj3)*(r00)*(sj8));
15907 IkReal x3451=((r10)*(sj3)*(sj8));
15908 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(cj8)*(x3445)*(x3448)))+(((IkReal(-1.00000000000000))*(cj8)*(x3445)*(x3449)))+(((IkReal(-1.00000000000000))*(r21)*(x3447)))+(((IkReal(-1.00000000000000))*(x3445)*(x3451)))+(((IkReal(-1.00000000000000))*(x3445)*(x3450)))+(((IkReal(-1.00000000000000))*(cj5)*(x3446))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(cj8)*(r21)*(x3445)))+(((x3447)*(x3448)))+(((x3447)*(x3449)))+(((cj5)*(x3450)))+(((cj5)*(x3451)))+(((IkReal(-1.00000000000000))*(x3445)*(x3446))))))) < IKFAST_ATAN2_MAGTHRESH )
15909  continue;
15910 j4array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(cj8)*(x3445)*(x3448)))+(((IkReal(-1.00000000000000))*(cj8)*(x3445)*(x3449)))+(((IkReal(-1.00000000000000))*(r21)*(x3447)))+(((IkReal(-1.00000000000000))*(x3445)*(x3451)))+(((IkReal(-1.00000000000000))*(x3445)*(x3450)))+(((IkReal(-1.00000000000000))*(cj5)*(x3446)))))), ((gconst51)*(((((IkReal(-1.00000000000000))*(cj8)*(r21)*(x3445)))+(((x3447)*(x3448)))+(((x3447)*(x3449)))+(((cj5)*(x3450)))+(((cj5)*(x3451)))+(((IkReal(-1.00000000000000))*(x3445)*(x3446)))))));
15911 sj4array[0]=IKsin(j4array[0]);
15912 cj4array[0]=IKcos(j4array[0]);
15913 if( j4array[0] > IKPI )
15914 {
15915  j4array[0]-=IK2PI;
15916 }
15917 else if( j4array[0] < -IKPI )
15918 { j4array[0]+=IK2PI;
15919 }
15920 j4valid[0] = true;
15921 for(int ij4 = 0; ij4 < 1; ++ij4)
15922 {
15923 if( !j4valid[ij4] )
15924 {
15925  continue;
15926 }
15927 _ij4[0] = ij4; _ij4[1] = -1;
15928 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15929 {
15930 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15931 {
15932  j4valid[iij4]=false; _ij4[1] = iij4; break;
15933 }
15934 }
15935 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15936 {
15937 IkReal evalcond[4];
15938 IkReal x3452=IKsin(j4);
15939 IkReal x3453=IKcos(j4);
15940 IkReal x3454=((IkReal(1.00000000000000))*(cj8));
15941 IkReal x3455=((cj3)*(r01));
15942 IkReal x3456=((cj3)*(r00));
15943 IkReal x3457=((cj7)*(cj8));
15944 IkReal x3458=((r11)*(sj3));
15945 IkReal x3459=((IkReal(1.00000000000000))*(sj8));
15946 IkReal x3460=((r10)*(sj3));
15947 IkReal x3461=((sj5)*(x3453));
15948 IkReal x3462=((cj5)*(x3452));
15949 IkReal x3463=((cj5)*(x3453));
15950 IkReal x3464=((sj5)*(x3452));
15951 IkReal x3465=((x3462)+(x3461));
15952 evalcond[0]=((((cj8)*(r21)))+(x3465)+(((r20)*(sj8))));
15953 evalcond[1]=((((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3454)))+(x3464)+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(x3463)))+(((cj7)*(r21)*(sj8))));
15954 evalcond[2]=((x3463)+(((IkReal(-1.00000000000000))*(x3454)*(x3455)))+(((IkReal(-1.00000000000000))*(x3454)*(x3458)))+(((IkReal(-1.00000000000000))*(x3459)*(x3460)))+(((IkReal(-1.00000000000000))*(x3464)))+(((IkReal(-1.00000000000000))*(x3456)*(x3459))));
15955 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x3455)*(x3459)))+(x3465)+(((x3457)*(x3460)))+(((IkReal(-1.00000000000000))*(cj7)*(x3458)*(x3459)))+(((cj3)*(r02)*(sj7)))+(((x3456)*(x3457))));
15956 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
15957 {
15958 continue;
15959 }
15960 }
15961 
15962 {
15963 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15964 vinfos[0].jointtype = 1;
15965 vinfos[0].foffset = j3;
15966 vinfos[0].indices[0] = _ij3[0];
15967 vinfos[0].indices[1] = _ij3[1];
15968 vinfos[0].maxsolutions = _nj3;
15969 vinfos[1].jointtype = 1;
15970 vinfos[1].foffset = j4;
15971 vinfos[1].indices[0] = _ij4[0];
15972 vinfos[1].indices[1] = _ij4[1];
15973 vinfos[1].maxsolutions = _nj4;
15974 vinfos[2].jointtype = 1;
15975 vinfos[2].foffset = j5;
15976 vinfos[2].indices[0] = _ij5[0];
15977 vinfos[2].indices[1] = _ij5[1];
15978 vinfos[2].maxsolutions = _nj5;
15979 vinfos[3].jointtype = 1;
15980 vinfos[3].foffset = j6;
15981 vinfos[3].indices[0] = _ij6[0];
15982 vinfos[3].indices[1] = _ij6[1];
15983 vinfos[3].maxsolutions = _nj6;
15984 vinfos[4].jointtype = 1;
15985 vinfos[4].foffset = j7;
15986 vinfos[4].indices[0] = _ij7[0];
15987 vinfos[4].indices[1] = _ij7[1];
15988 vinfos[4].maxsolutions = _nj7;
15989 vinfos[5].jointtype = 1;
15990 vinfos[5].foffset = j8;
15991 vinfos[5].indices[0] = _ij8[0];
15992 vinfos[5].indices[1] = _ij8[1];
15993 vinfos[5].maxsolutions = _nj8;
15994 std::vector<int> vfree(0);
15995 solutions.AddSolution(vinfos,vfree);
15996 }
15997 }
15998 }
15999 
16000 }
16001 
16002 }
16003 
16004 } else
16005 {
16006 {
16007 IkReal j4array[1], cj4array[1], sj4array[1];
16008 bool j4valid[1]={false};
16009 _nj4 = 1;
16010 IkReal x3466=((cj8)*(sj5));
16011 IkReal x3467=((sj5)*(sj8));
16012 IkReal x3468=((r22)*(sj7));
16013 IkReal x3469=((cj7)*(r20));
16014 IkReal x3470=((cj5)*(cj8));
16015 IkReal x3471=((cj7)*(r21));
16016 IkReal x3472=((cj5)*(sj8));
16017 if( IKabs(((gconst50)*(((((x3467)*(x3471)))+(((IkReal(-1.00000000000000))*(x3466)*(x3469)))+(((r20)*(x3472)))+(((r21)*(x3470)))+(((IkReal(-1.00000000000000))*(sj5)*(x3468))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(x3471)*(x3472)))+(((cj5)*(x3468)))+(((x3469)*(x3470)))+(((r20)*(x3467)))+(((r21)*(x3466))))))) < IKFAST_ATAN2_MAGTHRESH )
16018  continue;
16019 j4array[0]=IKatan2(((gconst50)*(((((x3467)*(x3471)))+(((IkReal(-1.00000000000000))*(x3466)*(x3469)))+(((r20)*(x3472)))+(((r21)*(x3470)))+(((IkReal(-1.00000000000000))*(sj5)*(x3468)))))), ((gconst50)*(((((IkReal(-1.00000000000000))*(x3471)*(x3472)))+(((cj5)*(x3468)))+(((x3469)*(x3470)))+(((r20)*(x3467)))+(((r21)*(x3466)))))));
16020 sj4array[0]=IKsin(j4array[0]);
16021 cj4array[0]=IKcos(j4array[0]);
16022 if( j4array[0] > IKPI )
16023 {
16024  j4array[0]-=IK2PI;
16025 }
16026 else if( j4array[0] < -IKPI )
16027 { j4array[0]+=IK2PI;
16028 }
16029 j4valid[0] = true;
16030 for(int ij4 = 0; ij4 < 1; ++ij4)
16031 {
16032 if( !j4valid[ij4] )
16033 {
16034  continue;
16035 }
16036 _ij4[0] = ij4; _ij4[1] = -1;
16037 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16038 {
16039 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16040 {
16041  j4valid[iij4]=false; _ij4[1] = iij4; break;
16042 }
16043 }
16044 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16045 {
16046 IkReal evalcond[4];
16047 IkReal x3473=IKsin(j4);
16048 IkReal x3474=IKcos(j4);
16049 IkReal x3475=((IkReal(1.00000000000000))*(cj8));
16050 IkReal x3476=((cj3)*(r01));
16051 IkReal x3477=((cj3)*(r00));
16052 IkReal x3478=((cj7)*(cj8));
16053 IkReal x3479=((r11)*(sj3));
16054 IkReal x3480=((IkReal(1.00000000000000))*(sj8));
16055 IkReal x3481=((r10)*(sj3));
16056 IkReal x3482=((sj5)*(x3474));
16057 IkReal x3483=((cj5)*(x3473));
16058 IkReal x3484=((cj5)*(x3474));
16059 IkReal x3485=((sj5)*(x3473));
16060 IkReal x3486=((x3483)+(x3482));
16061 evalcond[0]=((((cj8)*(r21)))+(x3486)+(((r20)*(sj8))));
16062 evalcond[1]=((x3485)+(((IkReal(-1.00000000000000))*(x3484)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3475)))+(((cj7)*(r21)*(sj8))));
16063 evalcond[2]=((x3484)+(((IkReal(-1.00000000000000))*(x3485)))+(((IkReal(-1.00000000000000))*(x3475)*(x3476)))+(((IkReal(-1.00000000000000))*(x3475)*(x3479)))+(((IkReal(-1.00000000000000))*(x3477)*(x3480)))+(((IkReal(-1.00000000000000))*(x3480)*(x3481))));
16064 evalcond[3]=((((r12)*(sj3)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(x3476)*(x3480)))+(((x3477)*(x3478)))+(x3486)+(((cj3)*(r02)*(sj7)))+(((x3478)*(x3481)))+(((IkReal(-1.00000000000000))*(cj7)*(x3479)*(x3480))));
16065 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
16066 {
16067 continue;
16068 }
16069 }
16070 
16071 {
16072 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16073 vinfos[0].jointtype = 1;
16074 vinfos[0].foffset = j3;
16075 vinfos[0].indices[0] = _ij3[0];
16076 vinfos[0].indices[1] = _ij3[1];
16077 vinfos[0].maxsolutions = _nj3;
16078 vinfos[1].jointtype = 1;
16079 vinfos[1].foffset = j4;
16080 vinfos[1].indices[0] = _ij4[0];
16081 vinfos[1].indices[1] = _ij4[1];
16082 vinfos[1].maxsolutions = _nj4;
16083 vinfos[2].jointtype = 1;
16084 vinfos[2].foffset = j5;
16085 vinfos[2].indices[0] = _ij5[0];
16086 vinfos[2].indices[1] = _ij5[1];
16087 vinfos[2].maxsolutions = _nj5;
16088 vinfos[3].jointtype = 1;
16089 vinfos[3].foffset = j6;
16090 vinfos[3].indices[0] = _ij6[0];
16091 vinfos[3].indices[1] = _ij6[1];
16092 vinfos[3].maxsolutions = _nj6;
16093 vinfos[4].jointtype = 1;
16094 vinfos[4].foffset = j7;
16095 vinfos[4].indices[0] = _ij7[0];
16096 vinfos[4].indices[1] = _ij7[1];
16097 vinfos[4].maxsolutions = _nj7;
16098 vinfos[5].jointtype = 1;
16099 vinfos[5].foffset = j8;
16100 vinfos[5].indices[0] = _ij8[0];
16101 vinfos[5].indices[1] = _ij8[1];
16102 vinfos[5].maxsolutions = _nj8;
16103 std::vector<int> vfree(0);
16104 solutions.AddSolution(vinfos,vfree);
16105 }
16106 }
16107 }
16108 
16109 }
16110 
16111 }
16112 
16113 } else
16114 {
16115 IkReal x3487=((cj3)*(cj8));
16116 IkReal x3488=((IkReal(1.00000000000000))*(sj7));
16117 IkReal x3489=((cj8)*(npx));
16118 IkReal x3490=((cj8)*(sj3));
16119 IkReal x3491=((npy)*(sj8));
16120 IkReal x3492=((r02)*(sj3));
16121 IkReal x3493=((IkReal(1.00000000000000))*(r11));
16122 IkReal x3494=((cj3)*(r12));
16123 IkReal x3495=((IkReal(1.00000000000000))*(cj7));
16124 IkReal x3496=((sj3)*(sj8));
16125 IkReal x3497=((IkReal(1.00000000000000))*(cj3)*(sj8));
16126 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j6)), IkReal(6.28318530717959))));
16127 evalcond[1]=((IkReal(-0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
16128 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
16129 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(x3489)*(x3495)))+(((IkReal(-1.00000000000000))*(npz)*(x3488)))+(((IkReal(0.250000000000000))*(cj5)))+(((cj7)*(x3491))));
16130 evalcond[4]=((IkReal(1.00000000000000))+(((r01)*(x3490)))+(((r00)*(x3496)))+(((IkReal(-1.00000000000000))*(r10)*(x3497)))+(((IkReal(-1.00000000000000))*(x3487)*(x3493))));
16131 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((sj7)*(x3491)))+(((cj7)*(npz)))+(((IkReal(-0.250000000000000))*(sj5)))+(((IkReal(-1.00000000000000))*(x3488)*(x3489))));
16132 evalcond[6]=((((IkReal(-1.00000000000000))*(x3490)*(x3493)))+(((IkReal(-1.00000000000000))*(r00)*(x3497)))+(((IkReal(-1.00000000000000))*(r10)*(x3496)))+(((IkReal(-1.00000000000000))*(r01)*(x3487))));
16133 evalcond[7]=((((sj7)*(x3494)))+(((IkReal(-1.00000000000000))*(r00)*(x3490)*(x3495)))+(((IkReal(-1.00000000000000))*(x3488)*(x3492)))+(((cj7)*(r01)*(x3496)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x3493)))+(((cj7)*(r10)*(x3487))));
16134 evalcond[8]=((((IkReal(-1.00000000000000))*(x3494)*(x3495)))+(((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x3488)))+(((r01)*(sj7)*(x3496)))+(((IkReal(-1.00000000000000))*(r00)*(x3488)*(x3490)))+(((r10)*(sj7)*(x3487)))+(((cj7)*(x3492))));
16135 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
16136 {
16137 {
16138 IkReal dummyeval[1];
16139 IkReal gconst52;
16140 gconst52=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
16141 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
16142 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
16143 {
16144 {
16145 IkReal dummyeval[1];
16146 IkReal gconst53;
16147 gconst53=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
16148 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
16149 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
16150 {
16151 continue;
16152 
16153 } else
16154 {
16155 {
16156 IkReal j4array[1], cj4array[1], sj4array[1];
16157 bool j4valid[1]={false};
16158 _nj4 = 1;
16159 IkReal x3498=((cj3)*(cj5));
16160 IkReal x3499=((r02)*(sj7));
16161 IkReal x3500=((cj5)*(sj7));
16162 IkReal x3501=((cj3)*(sj5));
16163 IkReal x3502=((r11)*(sj3));
16164 IkReal x3503=((r10)*(sj3));
16165 IkReal x3504=((r12)*(sj3));
16166 IkReal x3505=((sj5)*(sj7));
16167 IkReal x3506=((cj7)*(cj8)*(sj5));
16168 IkReal x3507=((IkReal(1.00000000000000))*(cj7)*(sj8));
16169 IkReal x3508=((cj5)*(cj7)*(cj8));
16170 if( IKabs(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((x3500)*(x3504)))+(((x3498)*(x3499)))+(((IkReal(-1.00000000000000))*(r20)*(x3506)))+(((cj7)*(cj8)*(r00)*(x3498)))+(((IkReal(-1.00000000000000))*(r01)*(x3498)*(x3507)))+(((IkReal(-1.00000000000000))*(cj5)*(x3502)*(x3507)))+(((x3503)*(x3508)))+(((IkReal(-1.00000000000000))*(r22)*(x3505))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((cj7)*(cj8)*(r00)*(x3501)))+(((r20)*(x3508)))+(((IkReal(-1.00000000000000))*(r01)*(x3501)*(x3507)))+(((x3499)*(x3501)))+(((IkReal(-1.00000000000000))*(sj5)*(x3502)*(x3507)))+(((r22)*(x3500)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3507)))+(((x3503)*(x3506)))+(((x3504)*(x3505))))))) < IKFAST_ATAN2_MAGTHRESH )
16171  continue;
16172 j4array[0]=IKatan2(((gconst53)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((x3500)*(x3504)))+(((x3498)*(x3499)))+(((IkReal(-1.00000000000000))*(r20)*(x3506)))+(((cj7)*(cj8)*(r00)*(x3498)))+(((IkReal(-1.00000000000000))*(r01)*(x3498)*(x3507)))+(((IkReal(-1.00000000000000))*(cj5)*(x3502)*(x3507)))+(((x3503)*(x3508)))+(((IkReal(-1.00000000000000))*(r22)*(x3505)))))), ((gconst53)*(((((cj7)*(cj8)*(r00)*(x3501)))+(((r20)*(x3508)))+(((IkReal(-1.00000000000000))*(r01)*(x3501)*(x3507)))+(((x3499)*(x3501)))+(((IkReal(-1.00000000000000))*(sj5)*(x3502)*(x3507)))+(((r22)*(x3500)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3507)))+(((x3503)*(x3506)))+(((x3504)*(x3505)))))));
16173 sj4array[0]=IKsin(j4array[0]);
16174 cj4array[0]=IKcos(j4array[0]);
16175 if( j4array[0] > IKPI )
16176 {
16177  j4array[0]-=IK2PI;
16178 }
16179 else if( j4array[0] < -IKPI )
16180 { j4array[0]+=IK2PI;
16181 }
16182 j4valid[0] = true;
16183 for(int ij4 = 0; ij4 < 1; ++ij4)
16184 {
16185 if( !j4valid[ij4] )
16186 {
16187  continue;
16188 }
16189 _ij4[0] = ij4; _ij4[1] = -1;
16190 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16191 {
16192 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16193 {
16194  j4valid[iij4]=false; _ij4[1] = iij4; break;
16195 }
16196 }
16197 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16198 {
16199 IkReal evalcond[4];
16200 IkReal x3509=IKcos(j4);
16201 IkReal x3510=IKsin(j4);
16202 IkReal x3511=((IkReal(1.00000000000000))*(cj7));
16203 IkReal x3512=((cj8)*(r20));
16204 IkReal x3513=((cj3)*(r02));
16205 IkReal x3514=((IkReal(1.00000000000000))*(sj7));
16206 IkReal x3515=((sj3)*(sj7));
16207 IkReal x3516=((r21)*(sj8));
16208 IkReal x3517=((cj8)*(r10));
16209 IkReal x3518=((sj5)*(x3509));
16210 IkReal x3519=((cj5)*(x3510));
16211 IkReal x3520=((r11)*(sj3)*(sj8));
16212 IkReal x3521=((cj3)*(cj8)*(r00));
16213 IkReal x3522=((cj5)*(x3509));
16214 IkReal x3523=((cj3)*(r01)*(sj8));
16215 IkReal x3524=((sj5)*(x3510));
16216 IkReal x3525=((x3519)+(x3518));
16217 evalcond[0]=((((IkReal(-1.00000000000000))*(x3522)))+(((cj7)*(x3516)))+(((IkReal(-1.00000000000000))*(x3511)*(x3512)))+(x3524)+(((IkReal(-1.00000000000000))*(r22)*(x3514))));
16218 evalcond[1]=((((IkReal(-1.00000000000000))*(x3512)*(x3514)))+(x3525)+(((sj7)*(x3516)))+(((cj7)*(r22))));
16219 evalcond[2]=((((cj7)*(x3521)))+(x3525)+(((IkReal(-1.00000000000000))*(x3511)*(x3523)))+(((IkReal(-1.00000000000000))*(x3511)*(x3520)))+(((sj7)*(x3513)))+(((r12)*(x3515)))+(((cj7)*(sj3)*(x3517))));
16220 evalcond[3]=((((IkReal(-1.00000000000000))*(x3524)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3511)))+(((IkReal(-1.00000000000000))*(x3511)*(x3513)))+(x3522)+(((x3515)*(x3517)))+(((sj7)*(x3521)))+(((IkReal(-1.00000000000000))*(x3514)*(x3520)))+(((IkReal(-1.00000000000000))*(x3514)*(x3523))));
16221 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
16222 {
16223 continue;
16224 }
16225 }
16226 
16227 {
16228 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16229 vinfos[0].jointtype = 1;
16230 vinfos[0].foffset = j3;
16231 vinfos[0].indices[0] = _ij3[0];
16232 vinfos[0].indices[1] = _ij3[1];
16233 vinfos[0].maxsolutions = _nj3;
16234 vinfos[1].jointtype = 1;
16235 vinfos[1].foffset = j4;
16236 vinfos[1].indices[0] = _ij4[0];
16237 vinfos[1].indices[1] = _ij4[1];
16238 vinfos[1].maxsolutions = _nj4;
16239 vinfos[2].jointtype = 1;
16240 vinfos[2].foffset = j5;
16241 vinfos[2].indices[0] = _ij5[0];
16242 vinfos[2].indices[1] = _ij5[1];
16243 vinfos[2].maxsolutions = _nj5;
16244 vinfos[3].jointtype = 1;
16245 vinfos[3].foffset = j6;
16246 vinfos[3].indices[0] = _ij6[0];
16247 vinfos[3].indices[1] = _ij6[1];
16248 vinfos[3].maxsolutions = _nj6;
16249 vinfos[4].jointtype = 1;
16250 vinfos[4].foffset = j7;
16251 vinfos[4].indices[0] = _ij7[0];
16252 vinfos[4].indices[1] = _ij7[1];
16253 vinfos[4].maxsolutions = _nj7;
16254 vinfos[5].jointtype = 1;
16255 vinfos[5].foffset = j8;
16256 vinfos[5].indices[0] = _ij8[0];
16257 vinfos[5].indices[1] = _ij8[1];
16258 vinfos[5].maxsolutions = _nj8;
16259 std::vector<int> vfree(0);
16260 solutions.AddSolution(vinfos,vfree);
16261 }
16262 }
16263 }
16264 
16265 }
16266 
16267 }
16268 
16269 } else
16270 {
16271 {
16272 IkReal j4array[1], cj4array[1], sj4array[1];
16273 bool j4valid[1]={false};
16274 _nj4 = 1;
16275 IkReal x3526=((r21)*(sj8));
16276 IkReal x3527=((sj5)*(sj7));
16277 IkReal x3528=((cj5)*(sj7));
16278 IkReal x3529=((cj5)*(cj7));
16279 IkReal x3530=((cj8)*(r20));
16280 IkReal x3531=((cj7)*(sj5));
16281 if( IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(x3530)*(x3531)))+(((x3526)*(x3528)))+(((r22)*(x3529)))+(((IkReal(-1.00000000000000))*(r22)*(x3527)))+(((IkReal(-1.00000000000000))*(x3528)*(x3530)))+(((x3526)*(x3531))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((x3526)*(x3527)))+(((r22)*(x3531)))+(((IkReal(-1.00000000000000))*(x3526)*(x3529)))+(((r22)*(x3528)))+(((x3529)*(x3530)))+(((IkReal(-1.00000000000000))*(x3527)*(x3530))))))) < IKFAST_ATAN2_MAGTHRESH )
16282  continue;
16283 j4array[0]=IKatan2(((gconst52)*(((((IkReal(-1.00000000000000))*(x3530)*(x3531)))+(((x3526)*(x3528)))+(((r22)*(x3529)))+(((IkReal(-1.00000000000000))*(r22)*(x3527)))+(((IkReal(-1.00000000000000))*(x3528)*(x3530)))+(((x3526)*(x3531)))))), ((gconst52)*(((((x3526)*(x3527)))+(((r22)*(x3531)))+(((IkReal(-1.00000000000000))*(x3526)*(x3529)))+(((r22)*(x3528)))+(((x3529)*(x3530)))+(((IkReal(-1.00000000000000))*(x3527)*(x3530)))))));
16284 sj4array[0]=IKsin(j4array[0]);
16285 cj4array[0]=IKcos(j4array[0]);
16286 if( j4array[0] > IKPI )
16287 {
16288  j4array[0]-=IK2PI;
16289 }
16290 else if( j4array[0] < -IKPI )
16291 { j4array[0]+=IK2PI;
16292 }
16293 j4valid[0] = true;
16294 for(int ij4 = 0; ij4 < 1; ++ij4)
16295 {
16296 if( !j4valid[ij4] )
16297 {
16298  continue;
16299 }
16300 _ij4[0] = ij4; _ij4[1] = -1;
16301 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16302 {
16303 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16304 {
16305  j4valid[iij4]=false; _ij4[1] = iij4; break;
16306 }
16307 }
16308 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16309 {
16310 IkReal evalcond[4];
16311 IkReal x3532=IKcos(j4);
16312 IkReal x3533=IKsin(j4);
16313 IkReal x3534=((IkReal(1.00000000000000))*(cj7));
16314 IkReal x3535=((cj8)*(r20));
16315 IkReal x3536=((cj3)*(r02));
16316 IkReal x3537=((IkReal(1.00000000000000))*(sj7));
16317 IkReal x3538=((sj3)*(sj7));
16318 IkReal x3539=((r21)*(sj8));
16319 IkReal x3540=((cj8)*(r10));
16320 IkReal x3541=((sj5)*(x3532));
16321 IkReal x3542=((cj5)*(x3533));
16322 IkReal x3543=((r11)*(sj3)*(sj8));
16323 IkReal x3544=((cj3)*(cj8)*(r00));
16324 IkReal x3545=((cj5)*(x3532));
16325 IkReal x3546=((cj3)*(r01)*(sj8));
16326 IkReal x3547=((sj5)*(x3533));
16327 IkReal x3548=((x3541)+(x3542));
16328 evalcond[0]=((x3547)+(((cj7)*(x3539)))+(((IkReal(-1.00000000000000))*(x3545)))+(((IkReal(-1.00000000000000))*(r22)*(x3537)))+(((IkReal(-1.00000000000000))*(x3534)*(x3535))));
16329 evalcond[1]=((((IkReal(-1.00000000000000))*(x3535)*(x3537)))+(((sj7)*(x3539)))+(x3548)+(((cj7)*(r22))));
16330 evalcond[2]=((((r12)*(x3538)))+(((sj7)*(x3536)))+(x3548)+(((IkReal(-1.00000000000000))*(x3534)*(x3546)))+(((IkReal(-1.00000000000000))*(x3534)*(x3543)))+(((cj7)*(x3544)))+(((cj7)*(sj3)*(x3540))));
16331 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3534)))+(((sj7)*(x3544)))+(x3545)+(((x3538)*(x3540)))+(((IkReal(-1.00000000000000))*(x3547)))+(((IkReal(-1.00000000000000))*(x3537)*(x3546)))+(((IkReal(-1.00000000000000))*(x3537)*(x3543)))+(((IkReal(-1.00000000000000))*(x3534)*(x3536))));
16332 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
16333 {
16334 continue;
16335 }
16336 }
16337 
16338 {
16339 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16340 vinfos[0].jointtype = 1;
16341 vinfos[0].foffset = j3;
16342 vinfos[0].indices[0] = _ij3[0];
16343 vinfos[0].indices[1] = _ij3[1];
16344 vinfos[0].maxsolutions = _nj3;
16345 vinfos[1].jointtype = 1;
16346 vinfos[1].foffset = j4;
16347 vinfos[1].indices[0] = _ij4[0];
16348 vinfos[1].indices[1] = _ij4[1];
16349 vinfos[1].maxsolutions = _nj4;
16350 vinfos[2].jointtype = 1;
16351 vinfos[2].foffset = j5;
16352 vinfos[2].indices[0] = _ij5[0];
16353 vinfos[2].indices[1] = _ij5[1];
16354 vinfos[2].maxsolutions = _nj5;
16355 vinfos[3].jointtype = 1;
16356 vinfos[3].foffset = j6;
16357 vinfos[3].indices[0] = _ij6[0];
16358 vinfos[3].indices[1] = _ij6[1];
16359 vinfos[3].maxsolutions = _nj6;
16360 vinfos[4].jointtype = 1;
16361 vinfos[4].foffset = j7;
16362 vinfos[4].indices[0] = _ij7[0];
16363 vinfos[4].indices[1] = _ij7[1];
16364 vinfos[4].maxsolutions = _nj7;
16365 vinfos[5].jointtype = 1;
16366 vinfos[5].foffset = j8;
16367 vinfos[5].indices[0] = _ij8[0];
16368 vinfos[5].indices[1] = _ij8[1];
16369 vinfos[5].maxsolutions = _nj8;
16370 std::vector<int> vfree(0);
16371 solutions.AddSolution(vinfos,vfree);
16372 }
16373 }
16374 }
16375 
16376 }
16377 
16378 }
16379 
16380 } else
16381 {
16382 IkReal x3549=((cj3)*(cj8));
16383 IkReal x3550=((IkReal(1.00000000000000))*(sj7));
16384 IkReal x3551=((cj8)*(npx));
16385 IkReal x3552=((cj8)*(sj3));
16386 IkReal x3553=((npy)*(sj8));
16387 IkReal x3554=((r02)*(sj3));
16388 IkReal x3555=((IkReal(1.00000000000000))*(r11));
16389 IkReal x3556=((cj3)*(r12));
16390 IkReal x3557=((IkReal(1.00000000000000))*(cj7));
16391 IkReal x3558=((sj3)*(sj8));
16392 IkReal x3559=((IkReal(1.00000000000000))*(cj3)*(sj8));
16393 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j6)), IkReal(6.28318530717959))));
16394 evalcond[1]=((IkReal(0.0950000000000000))+(((npx)*(sj8)))+(((cj8)*(npy))));
16395 evalcond[2]=((((cj8)*(r21)))+(((r20)*(sj8))));
16396 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj7)))+(((IkReal(-1.00000000000000))*(npz)*(x3550)))+(((IkReal(0.250000000000000))*(cj5)))+(((cj7)*(x3553)))+(((IkReal(-1.00000000000000))*(x3551)*(x3557))));
16397 evalcond[4]=((IkReal(-1.00000000000000))+(((r01)*(x3552)))+(((IkReal(-1.00000000000000))*(r10)*(x3559)))+(((r00)*(x3558)))+(((IkReal(-1.00000000000000))*(x3549)*(x3555))));
16398 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(0.0900000000000000))*(sj7)))+(((IkReal(0.250000000000000))*(sj5)))+(((sj7)*(x3553)))+(((IkReal(-1.00000000000000))*(x3550)*(x3551)))+(((cj7)*(npz))));
16399 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x3559)))+(((IkReal(-1.00000000000000))*(r10)*(x3558)))+(((IkReal(-1.00000000000000))*(x3552)*(x3555)))+(((IkReal(-1.00000000000000))*(r01)*(x3549))));
16400 evalcond[7]=((((IkReal(-1.00000000000000))*(cj3)*(cj7)*(sj8)*(x3555)))+(((cj7)*(r10)*(x3549)))+(((IkReal(-1.00000000000000))*(r00)*(x3552)*(x3557)))+(((cj7)*(r01)*(x3558)))+(((sj7)*(x3556)))+(((IkReal(-1.00000000000000))*(x3550)*(x3554))));
16401 evalcond[8]=((((IkReal(-1.00000000000000))*(cj3)*(r11)*(sj8)*(x3550)))+(((IkReal(-1.00000000000000))*(r00)*(x3550)*(x3552)))+(((r01)*(sj7)*(x3558)))+(((cj7)*(x3554)))+(((r10)*(sj7)*(x3549)))+(((IkReal(-1.00000000000000))*(x3556)*(x3557))));
16402 if( IKabs(evalcond[0]) < 0.0000010000000000 && IKabs(evalcond[1]) < 0.0000010000000000 && IKabs(evalcond[2]) < 0.0000010000000000 && IKabs(evalcond[3]) < 0.0000010000000000 && IKabs(evalcond[4]) < 0.0000010000000000 && IKabs(evalcond[5]) < 0.0000010000000000 && IKabs(evalcond[6]) < 0.0000010000000000 && IKabs(evalcond[7]) < 0.0000010000000000 && IKabs(evalcond[8]) < 0.0000010000000000 )
16403 {
16404 {
16405 IkReal dummyeval[1];
16406 IkReal gconst54;
16407 gconst54=IKsign((((cj5)*(cj5))+((sj5)*(sj5))));
16408 dummyeval[0]=(((cj5)*(cj5))+((sj5)*(sj5)));
16409 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
16410 {
16411 {
16412 IkReal dummyeval[1];
16413 IkReal gconst55;
16414 gconst55=IKsign(((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5))))));
16415 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj5)*(cj5))))+(((IkReal(-1.00000000000000))*((sj5)*(sj5)))));
16416 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
16417 {
16418 continue;
16419 
16420 } else
16421 {
16422 {
16423 IkReal j4array[1], cj4array[1], sj4array[1];
16424 bool j4valid[1]={false};
16425 _nj4 = 1;
16426 IkReal x3560=((cj3)*(cj5));
16427 IkReal x3561=((r02)*(sj7));
16428 IkReal x3562=((cj8)*(r00));
16429 IkReal x3563=((cj5)*(sj7));
16430 IkReal x3564=((cj5)*(sj3));
16431 IkReal x3565=((sj3)*(sj5));
16432 IkReal x3566=((IkReal(1.00000000000000))*(sj5));
16433 IkReal x3567=((cj3)*(cj7)*(sj5));
16434 IkReal x3568=((IkReal(1.00000000000000))*(cj7)*(sj8));
16435 IkReal x3569=((cj7)*(cj8)*(r10));
16436 IkReal x3570=((cj7)*(cj8)*(r20));
16437 if( IKabs(((gconst55)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x3566)))+(((IkReal(-1.00000000000000))*(x3566)*(x3570)))+(((cj7)*(x3560)*(x3562)))+(((IkReal(-1.00000000000000))*(r01)*(x3560)*(x3568)))+(((r12)*(sj3)*(x3563)))+(((x3564)*(x3569)))+(((IkReal(-1.00000000000000))*(r11)*(x3564)*(x3568)))+(((x3560)*(x3561))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((x3562)*(x3567)))+(((x3565)*(x3569)))+(((cj5)*(x3570)))+(((cj3)*(sj5)*(x3561)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x3566)))+(((r12)*(sj7)*(x3565)))+(((IkReal(-1.00000000000000))*(r11)*(x3565)*(x3568)))+(((r22)*(x3563)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3568))))))) < IKFAST_ATAN2_MAGTHRESH )
16438  continue;
16439 j4array[0]=IKatan2(((gconst55)*(((((cj7)*(r21)*(sj5)*(sj8)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)*(x3566)))+(((IkReal(-1.00000000000000))*(x3566)*(x3570)))+(((cj7)*(x3560)*(x3562)))+(((IkReal(-1.00000000000000))*(r01)*(x3560)*(x3568)))+(((r12)*(sj3)*(x3563)))+(((x3564)*(x3569)))+(((IkReal(-1.00000000000000))*(r11)*(x3564)*(x3568)))+(((x3560)*(x3561)))))), ((gconst55)*(((((x3562)*(x3567)))+(((x3565)*(x3569)))+(((cj5)*(x3570)))+(((cj3)*(sj5)*(x3561)))+(((IkReal(-1.00000000000000))*(cj3)*(cj7)*(r01)*(sj8)*(x3566)))+(((r12)*(sj7)*(x3565)))+(((IkReal(-1.00000000000000))*(r11)*(x3565)*(x3568)))+(((r22)*(x3563)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3568)))))));
16440 sj4array[0]=IKsin(j4array[0]);
16441 cj4array[0]=IKcos(j4array[0]);
16442 if( j4array[0] > IKPI )
16443 {
16444  j4array[0]-=IK2PI;
16445 }
16446 else if( j4array[0] < -IKPI )
16447 { j4array[0]+=IK2PI;
16448 }
16449 j4valid[0] = true;
16450 for(int ij4 = 0; ij4 < 1; ++ij4)
16451 {
16452 if( !j4valid[ij4] )
16453 {
16454  continue;
16455 }
16456 _ij4[0] = ij4; _ij4[1] = -1;
16457 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16458 {
16459 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16460 {
16461  j4valid[iij4]=false; _ij4[1] = iij4; break;
16462 }
16463 }
16464 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16465 {
16466 IkReal evalcond[4];
16467 IkReal x3571=IKcos(j4);
16468 IkReal x3572=IKsin(j4);
16469 IkReal x3573=((IkReal(1.00000000000000))*(cj7));
16470 IkReal x3574=((cj8)*(r20));
16471 IkReal x3575=((cj3)*(r02));
16472 IkReal x3576=((IkReal(1.00000000000000))*(sj7));
16473 IkReal x3577=((sj3)*(sj7));
16474 IkReal x3578=((r21)*(sj8));
16475 IkReal x3579=((IkReal(1.00000000000000))*(cj5));
16476 IkReal x3580=((cj8)*(r10));
16477 IkReal x3581=((sj5)*(x3572));
16478 IkReal x3582=((sj5)*(x3571));
16479 IkReal x3583=((r11)*(sj3)*(sj8));
16480 IkReal x3584=((cj3)*(cj8)*(r00));
16481 IkReal x3585=((cj3)*(r01)*(sj8));
16482 IkReal x3586=((x3571)*(x3579));
16483 evalcond[0]=((((cj7)*(x3578)))+(x3581)+(((IkReal(-1.00000000000000))*(x3573)*(x3574)))+(((IkReal(-1.00000000000000))*(r22)*(x3576)))+(((IkReal(-1.00000000000000))*(x3586))));
16484 evalcond[1]=((((IkReal(-1.00000000000000))*(x3574)*(x3576)))+(((IkReal(-1.00000000000000))*(x3572)*(x3579)))+(((sj7)*(x3578)))+(((IkReal(-1.00000000000000))*(x3582)))+(((cj7)*(r22))));
16485 evalcond[2]=((((IkReal(-1.00000000000000))*(x3573)*(x3583)))+(((IkReal(-1.00000000000000))*(x3573)*(x3585)))+(((cj5)*(x3572)))+(((cj7)*(sj3)*(x3580)))+(x3582)+(((r12)*(x3577)))+(((sj7)*(x3575)))+(((cj7)*(x3584))));
16486 evalcond[3]=((((IkReal(-1.00000000000000))*(x3576)*(x3585)))+(((IkReal(-1.00000000000000))*(x3576)*(x3583)))+(((sj7)*(x3584)))+(x3581)+(((IkReal(-1.00000000000000))*(x3573)*(x3575)))+(((x3577)*(x3580)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3573)))+(((IkReal(-1.00000000000000))*(x3586))));
16487 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
16488 {
16489 continue;
16490 }
16491 }
16492 
16493 {
16494 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16495 vinfos[0].jointtype = 1;
16496 vinfos[0].foffset = j3;
16497 vinfos[0].indices[0] = _ij3[0];
16498 vinfos[0].indices[1] = _ij3[1];
16499 vinfos[0].maxsolutions = _nj3;
16500 vinfos[1].jointtype = 1;
16501 vinfos[1].foffset = j4;
16502 vinfos[1].indices[0] = _ij4[0];
16503 vinfos[1].indices[1] = _ij4[1];
16504 vinfos[1].maxsolutions = _nj4;
16505 vinfos[2].jointtype = 1;
16506 vinfos[2].foffset = j5;
16507 vinfos[2].indices[0] = _ij5[0];
16508 vinfos[2].indices[1] = _ij5[1];
16509 vinfos[2].maxsolutions = _nj5;
16510 vinfos[3].jointtype = 1;
16511 vinfos[3].foffset = j6;
16512 vinfos[3].indices[0] = _ij6[0];
16513 vinfos[3].indices[1] = _ij6[1];
16514 vinfos[3].maxsolutions = _nj6;
16515 vinfos[4].jointtype = 1;
16516 vinfos[4].foffset = j7;
16517 vinfos[4].indices[0] = _ij7[0];
16518 vinfos[4].indices[1] = _ij7[1];
16519 vinfos[4].maxsolutions = _nj7;
16520 vinfos[5].jointtype = 1;
16521 vinfos[5].foffset = j8;
16522 vinfos[5].indices[0] = _ij8[0];
16523 vinfos[5].indices[1] = _ij8[1];
16524 vinfos[5].maxsolutions = _nj8;
16525 std::vector<int> vfree(0);
16526 solutions.AddSolution(vinfos,vfree);
16527 }
16528 }
16529 }
16530 
16531 }
16532 
16533 }
16534 
16535 } else
16536 {
16537 {
16538 IkReal j4array[1], cj4array[1], sj4array[1];
16539 bool j4valid[1]={false};
16540 _nj4 = 1;
16541 IkReal x3587=((cj7)*(sj5));
16542 IkReal x3588=((r21)*(sj8));
16543 IkReal x3589=((cj5)*(cj7));
16544 IkReal x3590=((cj8)*(r20));
16545 IkReal x3591=((IkReal(1.00000000000000))*(sj7));
16546 IkReal x3592=((sj5)*(sj7));
16547 if( IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(x3587)*(x3588)))+(((x3587)*(x3590)))+(((cj5)*(sj7)*(x3588)))+(((r22)*(x3592)))+(((IkReal(-1.00000000000000))*(cj5)*(x3590)*(x3591)))+(((r22)*(x3589))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(sj5)*(x3590)*(x3591)))+(((IkReal(-1.00000000000000))*(x3589)*(x3590)))+(((x3588)*(x3589)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x3591)))+(((x3588)*(x3592)))+(((r22)*(x3587))))))) < IKFAST_ATAN2_MAGTHRESH )
16548  continue;
16549 j4array[0]=IKatan2(((gconst54)*(((((IkReal(-1.00000000000000))*(x3587)*(x3588)))+(((x3587)*(x3590)))+(((cj5)*(sj7)*(x3588)))+(((r22)*(x3592)))+(((IkReal(-1.00000000000000))*(cj5)*(x3590)*(x3591)))+(((r22)*(x3589)))))), ((gconst54)*(((((IkReal(-1.00000000000000))*(sj5)*(x3590)*(x3591)))+(((IkReal(-1.00000000000000))*(x3589)*(x3590)))+(((x3588)*(x3589)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x3591)))+(((x3588)*(x3592)))+(((r22)*(x3587)))))));
16550 sj4array[0]=IKsin(j4array[0]);
16551 cj4array[0]=IKcos(j4array[0]);
16552 if( j4array[0] > IKPI )
16553 {
16554  j4array[0]-=IK2PI;
16555 }
16556 else if( j4array[0] < -IKPI )
16557 { j4array[0]+=IK2PI;
16558 }
16559 j4valid[0] = true;
16560 for(int ij4 = 0; ij4 < 1; ++ij4)
16561 {
16562 if( !j4valid[ij4] )
16563 {
16564  continue;
16565 }
16566 _ij4[0] = ij4; _ij4[1] = -1;
16567 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16568 {
16569 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16570 {
16571  j4valid[iij4]=false; _ij4[1] = iij4; break;
16572 }
16573 }
16574 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16575 {
16576 IkReal evalcond[4];
16577 IkReal x3593=IKcos(j4);
16578 IkReal x3594=IKsin(j4);
16579 IkReal x3595=((IkReal(1.00000000000000))*(cj7));
16580 IkReal x3596=((cj8)*(r20));
16581 IkReal x3597=((cj3)*(r02));
16582 IkReal x3598=((IkReal(1.00000000000000))*(sj7));
16583 IkReal x3599=((sj3)*(sj7));
16584 IkReal x3600=((r21)*(sj8));
16585 IkReal x3601=((IkReal(1.00000000000000))*(cj5));
16586 IkReal x3602=((cj8)*(r10));
16587 IkReal x3603=((sj5)*(x3594));
16588 IkReal x3604=((sj5)*(x3593));
16589 IkReal x3605=((r11)*(sj3)*(sj8));
16590 IkReal x3606=((cj3)*(cj8)*(r00));
16591 IkReal x3607=((cj3)*(r01)*(sj8));
16592 IkReal x3608=((x3593)*(x3601));
16593 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x3598)))+(x3603)+(((IkReal(-1.00000000000000))*(x3595)*(x3596)))+(((IkReal(-1.00000000000000))*(x3608)))+(((cj7)*(x3600))));
16594 evalcond[1]=((((IkReal(-1.00000000000000))*(x3594)*(x3601)))+(((IkReal(-1.00000000000000))*(x3604)))+(((IkReal(-1.00000000000000))*(x3596)*(x3598)))+(((cj7)*(r22)))+(((sj7)*(x3600))));
16595 evalcond[2]=((((cj5)*(x3594)))+(((r12)*(x3599)))+(((cj7)*(sj3)*(x3602)))+(x3604)+(((IkReal(-1.00000000000000))*(x3595)*(x3607)))+(((IkReal(-1.00000000000000))*(x3595)*(x3605)))+(((cj7)*(x3606)))+(((sj7)*(x3597))));
16596 evalcond[3]=((((IkReal(-1.00000000000000))*(x3598)*(x3605)))+(((IkReal(-1.00000000000000))*(x3598)*(x3607)))+(((x3599)*(x3602)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3595)))+(x3603)+(((IkReal(-1.00000000000000))*(x3595)*(x3597)))+(((IkReal(-1.00000000000000))*(x3608)))+(((sj7)*(x3606))));
16597 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
16598 {
16599 continue;
16600 }
16601 }
16602 
16603 {
16604 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16605 vinfos[0].jointtype = 1;
16606 vinfos[0].foffset = j3;
16607 vinfos[0].indices[0] = _ij3[0];
16608 vinfos[0].indices[1] = _ij3[1];
16609 vinfos[0].maxsolutions = _nj3;
16610 vinfos[1].jointtype = 1;
16611 vinfos[1].foffset = j4;
16612 vinfos[1].indices[0] = _ij4[0];
16613 vinfos[1].indices[1] = _ij4[1];
16614 vinfos[1].maxsolutions = _nj4;
16615 vinfos[2].jointtype = 1;
16616 vinfos[2].foffset = j5;
16617 vinfos[2].indices[0] = _ij5[0];
16618 vinfos[2].indices[1] = _ij5[1];
16619 vinfos[2].maxsolutions = _nj5;
16620 vinfos[3].jointtype = 1;
16621 vinfos[3].foffset = j6;
16622 vinfos[3].indices[0] = _ij6[0];
16623 vinfos[3].indices[1] = _ij6[1];
16624 vinfos[3].maxsolutions = _nj6;
16625 vinfos[4].jointtype = 1;
16626 vinfos[4].foffset = j7;
16627 vinfos[4].indices[0] = _ij7[0];
16628 vinfos[4].indices[1] = _ij7[1];
16629 vinfos[4].maxsolutions = _nj7;
16630 vinfos[5].jointtype = 1;
16631 vinfos[5].foffset = j8;
16632 vinfos[5].indices[0] = _ij8[0];
16633 vinfos[5].indices[1] = _ij8[1];
16634 vinfos[5].maxsolutions = _nj8;
16635 std::vector<int> vfree(0);
16636 solutions.AddSolution(vinfos,vfree);
16637 }
16638 }
16639 }
16640 
16641 }
16642 
16643 }
16644 
16645 } else
16646 {
16647 if( 1 )
16648 {
16649 continue;
16650 
16651 } else
16652 {
16653 }
16654 }
16655 }
16656 }
16657 }
16658 }
16659 
16660 } else
16661 {
16662 {
16663 IkReal j4array[1], cj4array[1], sj4array[1];
16664 bool j4valid[1]={false};
16665 _nj4 = 1;
16666 IkReal x3609=((r21)*(sj8));
16667 IkReal x3610=((IkReal(1.00000000000000))*(r22));
16668 IkReal x3611=((cj5)*(sj7));
16669 IkReal x3612=((cj6)*(cj7));
16670 IkReal x3613=((sj5)*(sj7));
16671 IkReal x3614=((cj5)*(cj8)*(r20));
16672 IkReal x3615=((IkReal(1.00000000000000))*(x3612));
16673 IkReal x3616=((cj8)*(r20)*(sj5));
16674 if( IKabs(((gconst47)*(((((x3612)*(x3616)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x3610)))+(((IkReal(-1.00000000000000))*(sj5)*(x3609)*(x3615)))+(((cj6)*(r22)*(x3613)))+(((cj8)*(r20)*(x3611)))+(((IkReal(-1.00000000000000))*(x3609)*(x3611))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(cj6)*(x3610)*(x3611)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x3610)))+(((cj5)*(x3609)*(x3612)))+(((IkReal(-1.00000000000000))*(x3614)*(x3615)))+(((cj8)*(r20)*(x3613)))+(((IkReal(-1.00000000000000))*(x3609)*(x3613))))))) < IKFAST_ATAN2_MAGTHRESH )
16675  continue;
16676 j4array[0]=IKatan2(((gconst47)*(((((x3612)*(x3616)))+(((IkReal(-1.00000000000000))*(cj5)*(cj7)*(x3610)))+(((IkReal(-1.00000000000000))*(sj5)*(x3609)*(x3615)))+(((cj6)*(r22)*(x3613)))+(((cj8)*(r20)*(x3611)))+(((IkReal(-1.00000000000000))*(x3609)*(x3611)))))), ((gconst47)*(((((IkReal(-1.00000000000000))*(cj6)*(x3610)*(x3611)))+(((IkReal(-1.00000000000000))*(cj7)*(sj5)*(x3610)))+(((cj5)*(x3609)*(x3612)))+(((IkReal(-1.00000000000000))*(x3614)*(x3615)))+(((cj8)*(r20)*(x3613)))+(((IkReal(-1.00000000000000))*(x3609)*(x3613)))))));
16677 sj4array[0]=IKsin(j4array[0]);
16678 cj4array[0]=IKcos(j4array[0]);
16679 if( j4array[0] > IKPI )
16680 {
16681  j4array[0]-=IK2PI;
16682 }
16683 else if( j4array[0] < -IKPI )
16684 { j4array[0]+=IK2PI;
16685 }
16686 j4valid[0] = true;
16687 for(int ij4 = 0; ij4 < 1; ++ij4)
16688 {
16689 if( !j4valid[ij4] )
16690 {
16691  continue;
16692 }
16693 _ij4[0] = ij4; _ij4[1] = -1;
16694 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16695 {
16696 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16697 {
16698  j4valid[iij4]=false; _ij4[1] = iij4; break;
16699 }
16700 }
16701 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16702 {
16703 IkReal evalcond[6];
16704 IkReal x3617=IKsin(j4);
16705 IkReal x3618=IKcos(j4);
16706 IkReal x3619=((IkReal(1.00000000000000))*(cj8));
16707 IkReal x3620=((cj3)*(r01));
16708 IkReal x3621=((IkReal(1.00000000000000))*(sj8));
16709 IkReal x3622=((r11)*(sj3));
16710 IkReal x3623=((cj3)*(r00));
16711 IkReal x3624=((IkReal(1.00000000000000))*(sj6));
16712 IkReal x3625=((IkReal(1.00000000000000))*(cj7));
16713 IkReal x3626=((cj3)*(r02));
16714 IkReal x3627=((sj3)*(sj7));
16715 IkReal x3628=((cj7)*(cj8));
16716 IkReal x3629=((r21)*(sj8));
16717 IkReal x3630=((r10)*(sj3));
16718 IkReal x3631=((sj5)*(x3618));
16719 IkReal x3632=((cj5)*(x3618));
16720 IkReal x3633=((cj6)*(x3617));
16721 IkReal x3634=((cj5)*(x3617));
16722 IkReal x3635=((sj5)*(x3617));
16723 evalcond[0]=((((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x3624)*(x3631)))+(((IkReal(-1.00000000000000))*(x3624)*(x3634)))+(((r20)*(sj8))));
16724 evalcond[1]=((((cj7)*(x3629)))+(x3635)+(((IkReal(-1.00000000000000))*(x3632)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3619))));
16725 evalcond[2]=((((IkReal(-1.00000000000000))*(r20)*(sj7)*(x3619)))+(((sj7)*(x3629)))+(((cj6)*(x3631)))+(((cj7)*(r22)))+(((cj5)*(x3633))));
16726 evalcond[3]=((((IkReal(-1.00000000000000))*(x3621)*(x3623)))+(((IkReal(-1.00000000000000))*(x3621)*(x3630)))+(((IkReal(-1.00000000000000))*(x3619)*(x3620)))+(((IkReal(-1.00000000000000))*(x3619)*(x3622)))+(((IkReal(-1.00000000000000))*(x3624)*(x3632)))+(((sj6)*(x3635))));
16727 evalcond[4]=((((sj7)*(x3626)))+(x3634)+(x3631)+(((x3628)*(x3630)))+(((IkReal(-1.00000000000000))*(cj7)*(x3620)*(x3621)))+(((r12)*(x3627)))+(((IkReal(-1.00000000000000))*(cj7)*(x3621)*(x3622)))+(((x3623)*(x3628))));
16728 evalcond[5]=((((IkReal(-1.00000000000000))*(x3625)*(x3626)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3625)))+(((cj8)*(r10)*(x3627)))+(((IkReal(-1.00000000000000))*(sj7)*(x3621)*(x3622)))+(((IkReal(-1.00000000000000))*(sj7)*(x3620)*(x3621)))+(((cj6)*(x3632)))+(((IkReal(-1.00000000000000))*(sj5)*(x3633)))+(((cj8)*(sj7)*(x3623))));
16729 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
16730 {
16731 continue;
16732 }
16733 }
16734 
16735 {
16736 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16737 vinfos[0].jointtype = 1;
16738 vinfos[0].foffset = j3;
16739 vinfos[0].indices[0] = _ij3[0];
16740 vinfos[0].indices[1] = _ij3[1];
16741 vinfos[0].maxsolutions = _nj3;
16742 vinfos[1].jointtype = 1;
16743 vinfos[1].foffset = j4;
16744 vinfos[1].indices[0] = _ij4[0];
16745 vinfos[1].indices[1] = _ij4[1];
16746 vinfos[1].maxsolutions = _nj4;
16747 vinfos[2].jointtype = 1;
16748 vinfos[2].foffset = j5;
16749 vinfos[2].indices[0] = _ij5[0];
16750 vinfos[2].indices[1] = _ij5[1];
16751 vinfos[2].maxsolutions = _nj5;
16752 vinfos[3].jointtype = 1;
16753 vinfos[3].foffset = j6;
16754 vinfos[3].indices[0] = _ij6[0];
16755 vinfos[3].indices[1] = _ij6[1];
16756 vinfos[3].maxsolutions = _nj6;
16757 vinfos[4].jointtype = 1;
16758 vinfos[4].foffset = j7;
16759 vinfos[4].indices[0] = _ij7[0];
16760 vinfos[4].indices[1] = _ij7[1];
16761 vinfos[4].maxsolutions = _nj7;
16762 vinfos[5].jointtype = 1;
16763 vinfos[5].foffset = j8;
16764 vinfos[5].indices[0] = _ij8[0];
16765 vinfos[5].indices[1] = _ij8[1];
16766 vinfos[5].maxsolutions = _nj8;
16767 std::vector<int> vfree(0);
16768 solutions.AddSolution(vinfos,vfree);
16769 }
16770 }
16771 }
16772 
16773 }
16774 
16775 }
16776 
16777 } else
16778 {
16779 {
16780 IkReal j4array[1], cj4array[1], sj4array[1];
16781 bool j4valid[1]={false};
16782 _nj4 = 1;
16783 IkReal x3636=((sj5)*(sj6));
16784 IkReal x3637=((r22)*(sj7));
16785 IkReal x3638=((r20)*(sj8));
16786 IkReal x3639=((cj8)*(r21));
16787 IkReal x3640=((cj5)*(sj6));
16788 IkReal x3641=((cj7)*(cj8)*(r20));
16789 IkReal x3642=((cj7)*(r21)*(sj8));
16790 if( IKabs(((gconst46)*(((((x3636)*(x3637)))+(((x3636)*(x3641)))+(((IkReal(-1.00000000000000))*(x3636)*(x3642)))+(((cj5)*(x3638)))+(((cj5)*(x3639))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((sj5)*(x3638)))+(((sj5)*(x3639)))+(((x3640)*(x3642)))+(((IkReal(-1.00000000000000))*(x3637)*(x3640)))+(((IkReal(-1.00000000000000))*(x3640)*(x3641))))))) < IKFAST_ATAN2_MAGTHRESH )
16791  continue;
16792 j4array[0]=IKatan2(((gconst46)*(((((x3636)*(x3637)))+(((x3636)*(x3641)))+(((IkReal(-1.00000000000000))*(x3636)*(x3642)))+(((cj5)*(x3638)))+(((cj5)*(x3639)))))), ((gconst46)*(((((sj5)*(x3638)))+(((sj5)*(x3639)))+(((x3640)*(x3642)))+(((IkReal(-1.00000000000000))*(x3637)*(x3640)))+(((IkReal(-1.00000000000000))*(x3640)*(x3641)))))));
16793 sj4array[0]=IKsin(j4array[0]);
16794 cj4array[0]=IKcos(j4array[0]);
16795 if( j4array[0] > IKPI )
16796 {
16797  j4array[0]-=IK2PI;
16798 }
16799 else if( j4array[0] < -IKPI )
16800 { j4array[0]+=IK2PI;
16801 }
16802 j4valid[0] = true;
16803 for(int ij4 = 0; ij4 < 1; ++ij4)
16804 {
16805 if( !j4valid[ij4] )
16806 {
16807  continue;
16808 }
16809 _ij4[0] = ij4; _ij4[1] = -1;
16810 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16811 {
16812 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16813 {
16814  j4valid[iij4]=false; _ij4[1] = iij4; break;
16815 }
16816 }
16817 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16818 {
16819 IkReal evalcond[6];
16820 IkReal x3643=IKsin(j4);
16821 IkReal x3644=IKcos(j4);
16822 IkReal x3645=((IkReal(1.00000000000000))*(cj8));
16823 IkReal x3646=((cj3)*(r01));
16824 IkReal x3647=((IkReal(1.00000000000000))*(sj8));
16825 IkReal x3648=((r11)*(sj3));
16826 IkReal x3649=((cj3)*(r00));
16827 IkReal x3650=((IkReal(1.00000000000000))*(sj6));
16828 IkReal x3651=((IkReal(1.00000000000000))*(cj7));
16829 IkReal x3652=((cj3)*(r02));
16830 IkReal x3653=((sj3)*(sj7));
16831 IkReal x3654=((cj7)*(cj8));
16832 IkReal x3655=((r21)*(sj8));
16833 IkReal x3656=((r10)*(sj3));
16834 IkReal x3657=((sj5)*(x3644));
16835 IkReal x3658=((cj5)*(x3644));
16836 IkReal x3659=((cj6)*(x3643));
16837 IkReal x3660=((cj5)*(x3643));
16838 IkReal x3661=((sj5)*(x3643));
16839 evalcond[0]=((((IkReal(-1.00000000000000))*(x3650)*(x3660)))+(((cj8)*(r21)))+(((IkReal(-1.00000000000000))*(x3650)*(x3657)))+(((r20)*(sj8))));
16840 evalcond[1]=((x3661)+(((IkReal(-1.00000000000000))*(x3658)))+(((IkReal(-1.00000000000000))*(cj7)*(r20)*(x3645)))+(((IkReal(-1.00000000000000))*(r22)*(sj7)))+(((cj7)*(x3655))));
16841 evalcond[2]=((((cj6)*(x3657)))+(((IkReal(-1.00000000000000))*(r20)*(sj7)*(x3645)))+(((sj7)*(x3655)))+(((cj5)*(x3659)))+(((cj7)*(r22))));
16842 evalcond[3]=((((sj6)*(x3661)))+(((IkReal(-1.00000000000000))*(x3645)*(x3648)))+(((IkReal(-1.00000000000000))*(x3645)*(x3646)))+(((IkReal(-1.00000000000000))*(x3650)*(x3658)))+(((IkReal(-1.00000000000000))*(x3647)*(x3649)))+(((IkReal(-1.00000000000000))*(x3647)*(x3656))));
16843 evalcond[4]=((((IkReal(-1.00000000000000))*(cj7)*(x3647)*(x3648)))+(((r12)*(x3653)))+(((x3649)*(x3654)))+(x3660)+(x3657)+(((x3654)*(x3656)))+(((sj7)*(x3652)))+(((IkReal(-1.00000000000000))*(cj7)*(x3646)*(x3647))));
16844 evalcond[5]=((((cj6)*(x3658)))+(((IkReal(-1.00000000000000))*(sj7)*(x3646)*(x3647)))+(((cj8)*(sj7)*(x3649)))+(((cj8)*(r10)*(x3653)))+(((IkReal(-1.00000000000000))*(sj5)*(x3659)))+(((IkReal(-1.00000000000000))*(x3651)*(x3652)))+(((IkReal(-1.00000000000000))*(sj7)*(x3647)*(x3648)))+(((IkReal(-1.00000000000000))*(r12)*(sj3)*(x3651))));
16845 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 || IKabs(evalcond[4]) > 0.000001 || IKabs(evalcond[5]) > 0.000001 )
16846 {
16847 continue;
16848 }
16849 }
16850 
16851 {
16852 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16853 vinfos[0].jointtype = 1;
16854 vinfos[0].foffset = j3;
16855 vinfos[0].indices[0] = _ij3[0];
16856 vinfos[0].indices[1] = _ij3[1];
16857 vinfos[0].maxsolutions = _nj3;
16858 vinfos[1].jointtype = 1;
16859 vinfos[1].foffset = j4;
16860 vinfos[1].indices[0] = _ij4[0];
16861 vinfos[1].indices[1] = _ij4[1];
16862 vinfos[1].maxsolutions = _nj4;
16863 vinfos[2].jointtype = 1;
16864 vinfos[2].foffset = j5;
16865 vinfos[2].indices[0] = _ij5[0];
16866 vinfos[2].indices[1] = _ij5[1];
16867 vinfos[2].maxsolutions = _nj5;
16868 vinfos[3].jointtype = 1;
16869 vinfos[3].foffset = j6;
16870 vinfos[3].indices[0] = _ij6[0];
16871 vinfos[3].indices[1] = _ij6[1];
16872 vinfos[3].maxsolutions = _nj6;
16873 vinfos[4].jointtype = 1;
16874 vinfos[4].foffset = j7;
16875 vinfos[4].indices[0] = _ij7[0];
16876 vinfos[4].indices[1] = _ij7[1];
16877 vinfos[4].maxsolutions = _nj7;
16878 vinfos[5].jointtype = 1;
16879 vinfos[5].foffset = j8;
16880 vinfos[5].indices[0] = _ij8[0];
16881 vinfos[5].indices[1] = _ij8[1];
16882 vinfos[5].maxsolutions = _nj8;
16883 std::vector<int> vfree(0);
16884 solutions.AddSolution(vinfos,vfree);
16885 }
16886 }
16887 }
16888 
16889 }
16890 
16891 }
16892 }
16893 }
16894 
16895 }
16896 
16897 }
16898 }
16899 }
16900 
16901 }
16902 
16903 }
16904  }
16905 }
16906 return solutions.GetNumSolutions()>0;
16907 }
16908 
16909 static inline bool checkconsistency8(const IkReal* Breal)
16910 {
16911  IkReal norm = 0.1;
16912  for(int i = 0; i < 7; ++i) {
16913  norm += IKabs(Breal[i]);
16914  }
16915  IkReal tol = 1e-5*norm; // have to increase the threshold since many computations are involved
16916  return IKabs(Breal[0]*Breal[1]-Breal[2]) < tol && IKabs(Breal[1]*Breal[1]-Breal[3]) < tol && IKabs(Breal[0]*Breal[3]-Breal[4]) < tol && IKabs(Breal[1]*Breal[3]-Breal[5]) < tol && IKabs(Breal[0]*Breal[5]-Breal[6]) < tol;
16917 }
16921 static inline void solvedialyticpoly8qep(const IkReal* matcoeffs, IkReal* rawroots, int& numroots)
16922 {
16923  const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
16924  IkReal IKFAST_ALIGNED16(M[16*16]) = {0};
16925  IkReal IKFAST_ALIGNED16(A[8*8]);
16926  IkReal IKFAST_ALIGNED16(work[16*16*15]);
16927  int ipiv[8];
16928  int info, coeffindex;
16929  const int worksize=16*16*15;
16930  const int matrixdim = 8;
16931  const int matrixdim2 = 16;
16932  numroots = 0;
16933  // first setup M = [0 I; -C -B] and A
16934  coeffindex = 0;
16935  for(int j = 0; j < 4; ++j) {
16936  for(int k = 0; k < 6; ++k) {
16937  M[matrixdim+(j+4)+2*matrixdim*k] = M[matrixdim+j+2*matrixdim*(k+2)] = -matcoeffs[coeffindex++];
16938  }
16939  }
16940  for(int j = 0; j < 4; ++j) {
16941  for(int k = 0; k < 6; ++k) {
16942  M[matrixdim+(j+4)+2*matrixdim*k+matrixdim*2*matrixdim] = M[matrixdim+j+2*matrixdim*(k+2)+matrixdim*2*matrixdim] = -matcoeffs[coeffindex++];
16943  }
16944  }
16945  for(int j = 0; j < 4; ++j) {
16946  for(int k = 0; k < 6; ++k) {
16947  A[(j+4)+matrixdim*k] = A[j+matrixdim*(k+2)] = matcoeffs[coeffindex++];
16948  }
16949  for(int k = 0; k < 2; ++k) {
16950  A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
16951  }
16952  }
16953  const IkReal lfpossibilities[4][4] = {{1,-1,1,1},{1,0,-2,1},{1,1,2,0},{1,-1,4,1}};
16954  int lfindex = -1;
16955  bool bsingular = true;
16956  do {
16957  dgetrf_(&matrixdim,&matrixdim,A,&matrixdim,&ipiv[0],&info);
16958  if( info == 0 ) {
16959  bsingular = false;
16960  for(int j = 0; j < matrixdim; ++j) {
16961  if( IKabs(A[j*matrixdim+j]) < 100*tol ) {
16962  bsingular = true;
16963  break;
16964  }
16965  }
16966  if( !bsingular ) {
16967  break;
16968  }
16969  }
16970  if( lfindex == 3 ) {
16971  break;
16972  }
16973  // transform by the linear functional
16974  lfindex++;
16975  const IkReal* lf = lfpossibilities[lfindex];
16976  // have to reinitialize A
16977  coeffindex = 0;
16978  for(int j = 0; j < 4; ++j) {
16979  for(int k = 0; k < 6; ++k) {
16980  IkReal a = matcoeffs[coeffindex+48], b = matcoeffs[coeffindex+24], c = matcoeffs[coeffindex];
16981  A[(j+4)+matrixdim*k] = A[j+matrixdim*(k+2)] = lf[0]*lf[0]*a+lf[0]*lf[2]*b+lf[2]*lf[2]*c;
16982  M[matrixdim+(j+4)+2*matrixdim*k] = M[matrixdim+j+2*matrixdim*(k+2)] = -(lf[1]*lf[1]*a + lf[1]*lf[3]*b + lf[3]*lf[3]*c);
16983  M[matrixdim+(j+4)+2*matrixdim*k+matrixdim*2*matrixdim] = M[matrixdim+j+2*matrixdim*(k+2)+matrixdim*2*matrixdim] = -(2*lf[0]*lf[1]*a + (lf[0]*lf[3]+lf[1]*lf[2])*b + 2*lf[2]*lf[3]*c);
16984  coeffindex++;
16985  }
16986  for(int k = 0; k < 2; ++k) {
16987  A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
16988  }
16989  }
16990  } while(lfindex<4);
16991 
16992  if( bsingular ) {
16993  return;
16994  }
16995  dgetrs_("No transpose", &matrixdim, &matrixdim2, A, &matrixdim, &ipiv[0], &M[matrixdim], &matrixdim2, &info);
16996  if( info != 0 ) {
16997  return;
16998  }
16999 
17000  // set identity in upper corner
17001  for(int j = 0; j < matrixdim; ++j) {
17002  M[matrixdim*2*matrixdim+j+matrixdim*2*j] = 1;
17003  }
17004  IkReal IKFAST_ALIGNED16(wr[16]);
17005  IkReal IKFAST_ALIGNED16(wi[16]);
17006  IkReal IKFAST_ALIGNED16(vr[16*16]);
17007  int one=1;
17008  dgeev_("N", "V", &matrixdim2, M, &matrixdim2, wr, wi,NULL, &one, vr, &matrixdim2, work, &worksize, &info);
17009  if( info != 0 ) {
17010  return;
17011  }
17012  IkReal Breal[matrixdim-1];
17013  for(int i = 0; i < matrixdim2; ++i) {
17014  if( IKabs(wi[i]) < tol*100 ) {
17015  IkReal* ev = vr+matrixdim2*i;
17016  if( IKabs(wr[i]) > 1 ) {
17017  ev += matrixdim;
17018  }
17019  // consistency has to be checked!!
17020  if( IKabs(ev[0]) < tol ) {
17021  continue;
17022  }
17023  IkReal iconst = 1/ev[0];
17024  for(int j = 1; j < matrixdim; ++j) {
17025  Breal[j-1] = ev[j]*iconst;
17026  }
17027  if( checkconsistency8(Breal) ) {
17028  if( lfindex >= 0 ) {
17029  const IkReal* lf = lfpossibilities[lfindex];
17030  rawroots[numroots++] = (wr[i]*lf[0]+lf[1])/(wr[i]*lf[2]+lf[3]);
17031  }
17032  else {
17033  rawroots[numroots++] = wr[i];
17034  }
17035  bool bsmall0=IKabs(ev[0]) > IKabs(ev[2]);
17036  bool bsmall1=IKabs(ev[0]) > IKabs(ev[1]);
17037  if( bsmall0 && bsmall1 ) {
17038  rawroots[numroots++] = ev[2]/ev[0];
17039  rawroots[numroots++] = ev[1]/ev[0];
17040  }
17041  else if( bsmall0 && !bsmall1 ) {
17042  rawroots[numroots++] = ev[3]/ev[1];
17043  rawroots[numroots++] = ev[1]/ev[0];
17044  }
17045  else if( !bsmall0 && bsmall1 ) {
17046  rawroots[numroots++] = ev[6]/ev[4];
17047  rawroots[numroots++] = ev[7]/ev[6];
17048  }
17049  else if( !bsmall0 && !bsmall1 ) {
17050  rawroots[numroots++] = ev[7]/ev[5];
17051  rawroots[numroots++] = ev[7]/ev[6];
17052  }
17053  }
17054  }
17055  }
17056 }};
17057 
17058 
17061 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
17062 IKSolver solver;
17063 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
17064 }
17065 
17066 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - NextageOpen (53b6c6feea19292c552a263dfc45aa26)>"; }
17067 
17068 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
17069 
17070 #ifdef IKFAST_NAMESPACE
17071 } // end namespace
17072 #endif
17073 
17074 #ifndef IKFAST_NO_MAIN
17075 #include <stdio.h>
17076 #include <stdlib.h>
17077 #ifdef IKFAST_NAMESPACE
17078 using namespace IKFAST_NAMESPACE;
17079 #endif
17080 int main(int argc, char** argv)
17081 {
17082  if( argc != 12+GetNumFreeParameters()+1 ) {
17083  printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
17084  "Returns the ik solutions given the transformation of the end effector specified by\n"
17085  "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
17086  "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
17087  return 1;
17088  }
17089 
17090  IkSolutionList<IkReal> solutions;
17091  std::vector<IkReal> vfree(GetNumFreeParameters());
17092  IkReal eerot[9],eetrans[3];
17093  eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
17094  eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
17095  eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
17096  for(std::size_t i = 0; i < vfree.size(); ++i)
17097  vfree[i] = atof(argv[13+i]);
17098  bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
17099 
17100  if( !bSuccess ) {
17101  fprintf(stderr,"Failed to get ik solution\n");
17102  return -1;
17103  }
17104 
17105  printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
17106  std::vector<IkReal> solvalues(GetNumJoints());
17107  for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
17108  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
17109  printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
17110  std::vector<IkReal> vsolfree(sol.GetFree().size());
17111  sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
17112  for( std::size_t j = 0; j < solvalues.size(); ++j)
17113  printf("%.15f, ", solvalues[j]);
17114  printf("\n");
17115  }
17116  return 0;
17117 }
17118 
17119 #endif
Definition: ikfast.h:43
#define IKPI
Definition: left_arm_ik.cpp:63
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:239
void zgetrf_(const int *m, const int *n, std::complex< double > *a, const int *lda, int *ipiv, int *info)
float IKsin(float f)
#define IKFAST_ATAN2_MAGTHRESH
IkReal sj8
void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi, double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info)
#define IKFAST_SINCOS_THRESH
Definition: left_arm_ik.cpp:99
#define IKFAST_ASSERT(b)
Definition: left_arm_ik.cpp:52
INLINE Rall1d< T, V, S > log(const Rall1d< T, V, S > &arg)
IKFAST_API int GetIkRealSize()
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:249
float IKabs(float f)
Definition: left_arm_ik.cpp:88
float IKatan2(float fy, float fx)
float IKasin(float f)
The discrete solutions are returned in this structure.
Definition: ikfast.h:65
int main(int argc, char **argv)
void dgetri_(const int *n, const double *a, const int *lda, int *ipiv, double *work, const int *lwork, int *info)
#define IK2PI
Definition: left_arm_ik.cpp:62
#define IKPI_2
Definition: left_arm_ik.cpp:64
float IKacos(float f)
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...
float IKsqrt(float f)
float IKfmod(float x, float y)
void dgesv_(const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info)
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
void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info)
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
IKFAST_API int GetNumJoints()
float IKtan(float f)
IKFAST_API const char * GetKinematicsHash()
INLINE Rall1d< T, V, S > asin(const Rall1d< T, V, S > &x)
virtual void Clear()=0
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
static bool checkconsistency8(const IkReal *Breal)
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)
IKFAST_API int * GetFreeParameters()
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
IKFAST_API const char * GetIkFastVersion()
#define IKFAST_SOLUTION_THRESH
void dgetrf_(const int *m, const int *n, double *a, const int *lda, int *ipiv, int *info)
IKFAST_API int GetNumFreeParameters()
#define IKFAST_ALIGNED16(x)
Definition: left_arm_ik.cpp:59
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
float IKsqr(float f)
Definition: left_arm_ik.cpp:91
unsigned char _nj8
float IKsign(float f)
#define IKFAST_STRINGIZE(s)
Definition: left_arm_ik.cpp:35
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
static void solvedialyticpoly8qep(const IkReal *matcoeffs, IkReal *rawroots, int &numroots)
Solve the det Ax^2+Bx+C = 0 problem using the Manocha and Canny method (1994)
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
Default implementation of IkSolutionListBase.
Definition: ikfast.h:229
#define IKFAST_COMPILE_ASSERT(x)
Definition: left_arm_ik.cpp:25
float IKcos(float f)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
#define IKFAST_VERSION
Header file for all ikfast c++ files/shared objects.
Definition: ikfast.h:41
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
manages all the solutions
Definition: ikfast.h:93
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
virtual size_t GetNumSolutions() const =0
returns the number of solutions stored
float IKlog(float f)
Definition: left_arm_ik.cpp:94
IKFAST_API int GetIkType()


nextage_ik_plugin
Author(s): TORK Developer 534o <534o@opensouce-robotics.tokyo.jp>
autogenerated on Wed Jun 17 2020 04:14:36